Skip to content

Commit 8c627bf

Browse files
committed
Patch applied to support teleporting of stage object. Send it a new position on cmd_pose, and it will move there. Patch courtesy of ros-simulation/stage_ros#39
1 parent a658fb9 commit 8c627bf

File tree

1 file changed

+21
-3
lines changed

1 file changed

+21
-3
lines changed

arc_stage/src/stageros.cpp

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@
5050
#include <nav_msgs/Odometry.h>
5151
#include <geometry_msgs/Twist.h>
5252
#include <rosgraph_msgs/Clock.h>
53+
#include <geometry_msgs/Pose2D.h>
5354

5455
#include <std_srvs/Empty.h>
5556

@@ -72,6 +73,7 @@
7273
#define BASE_MARKER_DETECTION "base_marker_detection"
7374
#define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth"
7475
#define CMD_VEL "cmd_vel"
76+
#define CMD_POSE "cmd_pose"
7577
#define NUM_DETECTORS 5
7678
static char * detectors[] = {"detector", "robot_detector", "victim_detector", "marker_detector", "debris_detector"};
7779

@@ -120,6 +122,7 @@ class StageNode
120122
std::vector<ros::Publisher> fiducial_pubs; //multiple fiducials
121123

122124
ros::Subscriber cmdvel_sub; //one cmd_vel subscriber
125+
ros::Subscriber cmdpose_sub; //one pos subscriber
123126

124127
VelocityCmdsDiffDrive cmdsDes;
125128
};
@@ -197,7 +200,10 @@ class StageNode
197200

198201
// Message callback for a MsgBaseVel message, which set velocities.
199202
void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);
200-
203+
204+
// Message callback for a Pose2D message, which sets pose.
205+
void cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg);
206+
201207
void cmdvelReceivedConstrainedDiffDrive(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);
202208

203209
// Service callback for soft reset
@@ -356,6 +362,18 @@ StageNode::ghfunc(Stg::Model* mod, StageNode* node)
356362

357363

358364

365+
void
366+
StageNode::cmdposeReceived(int idx, const boost::shared_ptr<geometry_msgs::Pose2D const>& msg)
367+
{
368+
boost::mutex::scoped_lock lock(msg_lock);
369+
Stg::Pose pose;
370+
pose.x = msg->x;
371+
pose.y = msg->y;
372+
pose.z =0;
373+
pose.a = msg->theta;
374+
this->positionmodels[idx]->SetPose(pose);
375+
}
376+
359377
bool
360378
StageNode::cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response)
361379
{
@@ -488,6 +506,8 @@ StageNode::SubscribeModels()
488506

489507
new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
490508
new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
509+
new_robot->cmdpose_sub = n_.subscribe<geometry_msgs::Pose2D>(mapName(CMD_POSE, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdposeReceived, this, r, _1));
510+
491511
if(!config_.constrainedDiffDrive) {
492512
new_robot->cmdvel_sub = n_.subscribe<geometry_msgs::Twist>(mapName(CMD_VEL, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::cmdvelReceived, this, r, _1));
493513
} else {
@@ -624,8 +644,6 @@ StageNode::WorldCallback()
624644
this->positionmodels[i]->SetSpeed(vAns, 0, wAns);
625645
}
626646
}
627-
628-
629647

630648
this->sim_time.fromSec(world->SimTimeNow() / 1e6);
631649
// We're not allowed to publish clock==0, because it used as a special

0 commit comments

Comments
 (0)