Skip to content

Commit

Permalink
allow parametrizing odometry frame id as well (useful if you have mul…
Browse files Browse the repository at this point in the history
…tiple robots)
  • Loading branch information
piyushk committed Feb 1, 2015
1 parent 0da2e6f commit 70fc5f8
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions src/segway_rmp_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -461,10 +461,11 @@ class SegwayRMPNode {
n->param("motor_timeout", this->segway_motor_timeout, 0.5);
// Get frame id parameter
n->param("frame_id", frame_id, std::string("base_link"));
n->param("odom_frame_id", odom_frame_id, std::string("odom"));
this->sss_msg.header.frame_id = this->frame_id;
this->odom_trans.header.frame_id = "odom";
this->odom_trans.header.frame_id = this->odom_frame_id;
this->odom_trans.child_frame_id = this->frame_id;
this->odom_msg.header.frame_id = "odom";
this->odom_msg.header.frame_id = this->odom_frame_id;
this->odom_msg.child_frame_id = this->frame_id;
// Get cmd_vel inversion parameters
n->param("invert_linear_vel_cmds", invert_x, false);
Expand Down Expand Up @@ -584,6 +585,7 @@ class SegwayRMPNode {
ros::Timer motor_timeout_timer;

std::string frame_id;
std::string odom_frame_id;
bool invert_x, invert_z;
bool broadcast_tf;

Expand Down

0 comments on commit 70fc5f8

Please sign in to comment.