Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 11 additions & 5 deletions src/stageros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <rosgraph_msgs/Clock.h>
#include <std_msgs/Int8.h>

#include <std_srvs/Empty.h>

Expand All @@ -61,6 +62,7 @@
#define BASE_SCAN "base_scan"
#define BASE_POSE_GROUND_TRUTH "base_pose_ground_truth"
#define CMD_VEL "cmd_vel"
#define STALLED "stalled"

// Our node
class StageNode
Expand Down Expand Up @@ -89,6 +91,7 @@ class StageNode
//ros publishers
ros::Publisher odom_pub; //one odom
ros::Publisher ground_truth_pub; //one ground truth
ros::Publisher stall_pub; // stall publisher

std::vector<ros::Publisher> image_pubs; //multiple images
std::vector<ros::Publisher> depth_pubs; //multiple depths
Expand Down Expand Up @@ -354,7 +357,8 @@ StageNode::SubscribeModels()
new_robot->odom_pub = n_.advertise<nav_msgs::Odometry>(mapName(ODOM, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
new_robot->ground_truth_pub = n_.advertise<nav_msgs::Odometry>(mapName(BASE_POSE_GROUND_TRUTH, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);
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));

new_robot->stall_pub = n_.advertise<std_msgs::Int8>(mapName(STALLED, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10);

for (size_t s = 0; s < new_robot->lasermodels.size(); ++s)
{
if (new_robot->lasermodels.size() == 1)
Expand Down Expand Up @@ -503,13 +507,15 @@ StageNode::WorldCallback()
odom_msg.twist.twist.linear.y = v.y;
odom_msg.twist.twist.angular.z = v.a;

//@todo Publish stall on a separate topic when one becomes available
//this->odomMsgs[r].stall = this->positionmodels[r]->Stall();
//
odom_msg.header.frame_id = mapName("odom", r, static_cast<Stg::Model*>(robotmodel->positionmodel));
odom_msg.header.stamp = sim_time;

robotmodel->odom_pub.publish(odom_msg);

//publish current stall state
std_msgs::Int8 stall_msg;
stall_msg.data = robotmodel->positionmodel->Stalled();
robotmodel->stall_pub.publish(stall_msg);

// broadcast odometry transform
tf::Quaternion odomQ;
Expand Down