mirror of
https://github.com/MAPIRlab/rf2o_laser_odometry.git
synced 2023-04-06 19:28:55 +08:00
extend rf2o namespace to class
This commit is contained in:
@@ -34,6 +34,7 @@
|
||||
#include <unsupported/Eigen/MatrixFunctions>
|
||||
|
||||
namespace rf2o {
|
||||
|
||||
template <typename T>
|
||||
inline int sign(T x) { return x<0 ? -1:1; }
|
||||
|
||||
@@ -61,7 +62,6 @@ inline Eigen::Matrix<T, 3, 3> matrixYaw(const T yaw)
|
||||
{
|
||||
return matrixRollPitchYaw<T>(0, 0, yaw);
|
||||
}
|
||||
} // namespace rf2o
|
||||
|
||||
class CLaserOdometry2D
|
||||
{
|
||||
@@ -175,4 +175,6 @@ protected:
|
||||
void Reset(const Pose3d& ini_pose/*, CObservation2DRangeScan scan*/);
|
||||
};
|
||||
|
||||
} /* namespace rf2o */
|
||||
|
||||
#endif // CLaserOdometry2D_H
|
||||
|
||||
@@ -17,6 +17,8 @@
|
||||
|
||||
#include "rf2o_laser_odometry/CLaserOdometry2D.h"
|
||||
|
||||
namespace rf2o {
|
||||
|
||||
// --------------------------------------------
|
||||
// CLaserOdometry2D
|
||||
//---------------------------------------------
|
||||
@@ -951,3 +953,5 @@ void CLaserOdometry2D::PoseUpdate()
|
||||
ang_speed = sum2 / last_m_ang_speeds.size();
|
||||
*/
|
||||
}
|
||||
|
||||
} /* namespace rf2o */
|
||||
|
||||
@@ -20,6 +20,8 @@
|
||||
#include <tf/transform_broadcaster.h>
|
||||
#include <tf/transform_listener.h>
|
||||
|
||||
namespace rf2o {
|
||||
|
||||
class CLaserOdometry2DNode : CLaserOdometry2D
|
||||
{
|
||||
public:
|
||||
@@ -249,6 +251,8 @@ void CLaserOdometry2DNode::publish()
|
||||
odom_pub.publish(odom);
|
||||
}
|
||||
|
||||
} /* namespace rf2o */
|
||||
|
||||
//-----------------------------------------------------------------------------------
|
||||
// MAIN
|
||||
//-----------------------------------------------------------------------------------
|
||||
@@ -256,7 +260,7 @@ int main(int argc, char** argv)
|
||||
{
|
||||
ros::init(argc, argv, "RF2O_LaserOdom");
|
||||
|
||||
CLaserOdometry2DNode myLaserOdomNode;
|
||||
rf2o::CLaserOdometry2DNode myLaserOdomNode;
|
||||
|
||||
ros::TimerOptions timer_opt;
|
||||
timer_opt.oneshot = false;
|
||||
@@ -264,7 +268,7 @@ int main(int argc, char** argv)
|
||||
timer_opt.callback_queue = ros::getGlobalCallbackQueue();
|
||||
timer_opt.tracked_object = ros::VoidConstPtr();
|
||||
|
||||
timer_opt.callback = boost::bind(&CLaserOdometry2DNode::process, &myLaserOdomNode, _1);
|
||||
timer_opt.callback = boost::bind(&rf2o::CLaserOdometry2DNode::process, &myLaserOdomNode, _1);
|
||||
timer_opt.period = ros::Rate(myLaserOdomNode.freq).expectedCycleTime();
|
||||
|
||||
ros::Timer rf2o_timer = ros::NodeHandle("~").createTimer(timer_opt);
|
||||
|
||||
Reference in New Issue
Block a user