{
node_=node;
- if(!node_.getParam("odometry_publisher/wheel_separation",wheelBase_))
+ ros::NodeHandle n("~");
+ if(!n.getParam("wheel_separation",wheelBase_))
{
ROS_ERROR("No 'wheel_separation' in node %s.",node_.getNamespace().c_str());
return;
}
- if(!node_.getParam("odometry_publisher/wheel_radius",wheelRadius_))
+ if(!n.getParam("wheel_radius",wheelRadius_))
{
ROS_ERROR("No 'wheel_radius' in node %s.",node_.getNamespace().c_str());
return;
phi_.setZero();
odom_frame_id_="odom";
- node_.param("odom_frame_id",odom_frame_id_,odom_frame_id_);
+ n.param("odom_frame_id",odom_frame_id_,odom_frame_id_);
base_frame_id_="base_link";
- node_.param("base_frame_id",base_frame_id_,base_frame_id_);
+ n.param("base_frame_id",base_frame_id_,base_frame_id_);
odomPub_=node_.advertise<nav_msgs::Odometry>("odom",100);
OdometryPublisher odomPublisher(node);
int rate=100;
- node.param("publish_rate",rate,rate);
+ ros::NodeHandle n("~");
+ n.param("publish_rate",rate,rate);
ros::Rate loop(rate);
while(ros::ok())