Skip to content

Commit

Permalink
update : lightIndicator ros interface via topic (msg type : Int8)
Browse files Browse the repository at this point in the history
  • Loading branch information
scifiswapnil committed May 1, 2020
1 parent 1d49387 commit 79ebf7c
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 5 deletions.
9 changes: 4 additions & 5 deletions src/stageros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@

// roscpp
#include <ros/ros.h>
// #include <std_msgs/Bool.h>
#include <boost/thread/mutex.hpp>
#include <boost/thread/thread.hpp>
#include <sensor_msgs/LaserScan.h>
Expand All @@ -49,7 +48,7 @@
#include <sensor_msgs/CameraInfo.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/Twist.h>
#include <std_msgs/Float64.h>
#include <std_msgs/Int8.h>
#include <rosgraph_msgs/Clock.h>

#include <std_srvs/Empty.h>
Expand Down Expand Up @@ -167,7 +166,7 @@ class StageNode

// Message callback for a MsgBaseVel message, which set velocities.
void cmdvelReceived(int idx, const boost::shared_ptr<geometry_msgs::Twist const>& msg);
void lightReceived(int idx, const boost::shared_ptr<std_msgs::Float64 const>& msg);
void lightReceived(int idx, const boost::shared_ptr<std_msgs::Int8 const>& msg);

// Service callback for soft reset
bool cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
Expand Down Expand Up @@ -273,7 +272,7 @@ StageNode::cb_reset_srv(std_srvs::Empty::Request& request, std_srvs::Empty::Resp


void
StageNode::lightReceived(int idx, const boost::shared_ptr<std_msgs::Float64 const>& msg)
StageNode::lightReceived(int idx, const boost::shared_ptr<std_msgs::Int8 const>& msg)
{
boost::mutex::scoped_lock lock(msg_lock);
this->lightmodels[idx]->SetState(msg->data) ;
Expand Down Expand Up @@ -405,7 +404,7 @@ StageNode::SubscribeModels()

for (size_t s = 0; s < new_robot->lasermodels.size(); ++s)
{
new_robot->light_subs.push_back(n_.subscribe<std_msgs::Float64>(mapName(LIGHTS, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::lightReceived, this, r, _1)));
new_robot->light_subs.push_back(n_.subscribe<std_msgs::Int8>(mapName(LIGHTS, r, static_cast<Stg::Model*>(new_robot->positionmodel)), 10, boost::bind(&StageNode::lightReceived, this, r, _1)));
}

for (size_t s = 0; s < new_robot->lasermodels.size(); ++s)
Expand Down
8 changes: 8 additions & 0 deletions world/willow-four-erratics.world
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@ define block model
gui_nose 0
)

define light lightindicator
(
# generic model properties
size [0.03 0.03 0.03]
color "red"
)

define topurg ranger
(
sensor(
Expand All @@ -24,6 +31,7 @@ define erratic position
origin [-0.05 0 0 0]
gui_nose 1
drive "diff"
light()
topurg(pose [ 0.050 0.000 0 0.000 ])
)

Expand Down

0 comments on commit 79ebf7c

Please sign in to comment.