diff --git a/src/stageros.cpp b/src/stageros.cpp index 39d040a..d33b8a9 100644 --- a/src/stageros.cpp +++ b/src/stageros.cpp @@ -49,6 +49,7 @@ #include #include #include +#include #include @@ -62,6 +63,7 @@ #define BASE_SCAN "base_scan" #define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth" #define CMD_VEL "cmd_vel" +#define CMD_POSE "cmd_pose" // Our node class StageNode @@ -97,6 +99,7 @@ class StageNode std::vector laser_pubs; //multiple lasers ros::Subscriber cmdvel_sub; //one cmd_vel subscriber + ros::Subscriber cmdpose_sub; //one pos subscriber }; std::vector robotmodels_; @@ -162,6 +165,9 @@ class StageNode // Message callback for a MsgBaseVel message, which set velocities. void cmdvelReceived(int idx, const boost::shared_ptr& msg); + // Message callback for a Pose2D message, which sets pose. + void cmdposeReceived(int idx, const boost::shared_ptr& msg); + // Service callback for soft reset bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response); @@ -271,6 +277,18 @@ StageNode::cmdvelReceived(int idx, const boost::shared_ptrbase_last_cmd = this->sim_time; } +void +StageNode::cmdposeReceived(int idx, const boost::shared_ptr& msg) +{ + boost::mutex::scoped_lock lock(msg_lock); + Stg::Pose pose; + pose.x = msg->x; + pose.y = msg->y; + pose.z =0; + pose.a = msg->theta; + this->positionmodels[idx]->SetPose(pose); +} + StageNode::StageNode(int argc, char** argv, bool gui, const char* fname, bool use_model_names) { this->use_model_names = use_model_names; @@ -363,6 +381,7 @@ StageNode::SubscribeModels() new_robot->odom_pub = n_.advertise(mapName(ODOM, r, static_cast(new_robot->positionmodel)), 10); new_robot->ground_truth_pub = n_.advertise(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast(new_robot->positionmodel)), 10); new_robot->cmdvel_sub = n_.subscribe(mapName(CMD_VEL, r, static_cast(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1)); + new_robot->cmdpose_sub = n_.subscribe(mapName(CMD_POSE, r, static_cast(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdposeReceived, this, r, _1)); for (size_t s = 0; s < new_robot->lasermodels.size(); ++s) {