28 #include <diagnostic_msgs/DiagnosticArray.h> 32 #include <std_msgs/ColorRGBA.h> 33 #include <std_msgs/UInt64.h> 34 #include <visualization_msgs/Marker.h> 35 #include <cob_light/ColorRGBAArray.h> 36 #include <cob_light/LightMode.h> 37 #include <cob_light/LightModes.h> 38 #include <cob_light/SetLightMode.h> 39 #include <cob_light/SetLightModeAction.h> 40 #include <cob_light/SetLightModeActionGoal.h> 41 #include <cob_light/SetLightModeActionResult.h> 42 #include <cob_light/StopLightMode.h> 67 num_params = params.
size();
70 std::string reason = params[1];
71 ROS_WARN(
"Shutdown request received. Reason: [%s]", reason.c_str());
90 std::string startup_mode;
97 diagnostic_msgs::DiagnosticStatus status;
103 ROS_WARN(
"Parameter 'invert_output' is missing. Using default Value: false");
104 _nh.
param<
bool>(
"invert_output", invert_output,
false);
108 ROS_WARN(
"Parameter 'devicedriver' is missing. Using default Value: cob_ledboard");
112 ROS_WARN(
"Parameter 'devicestring' is missing. Using default Value: /dev/ttyLed");
116 ROS_WARN(
"Parameter 'baudrate' is missing. Using default Value: 230400");
120 ROS_WARN(
"Parameter 'pubmarker' is missing. Using default Value: true");
124 ROS_WARN(
"Parameter 'marker_frame' is missing. Using default Value: /base_link");
128 ROS_WARN(
"Parameter 'sim_enabled' is missing. Using default Value: false");
133 ROS_WARN(
"Parameter 'startup_color' is missing. Using default Value: off");
142 _color.
r =
static_cast<double>(param_list[0]);
143 _color.
g =
static_cast<double>(param_list[1]);
144 _color.
b =
static_cast<double>(param_list[2]);
145 _color.
a =
static_cast<double>(param_list[3]);
149 ROS_WARN(
"Parameter 'startup_mode' is missing. Using default Value: None");
150 _nh.
param<std::string>(
"startup_mode", startup_mode,
"None");
153 ROS_WARN(
"Parameter 'num_leds' is missing. Using default Value: 58");
157 _nh.
param<
int>(
"led_offset", led_offset, 0);
178 ROS_INFO(
"Open Port on %s",_deviceString.c_str());
181 ROS_INFO(
"Serial connection on %s succeeded.", _deviceString.c_str());
183 status.message =
"light controller running";
185 if(_deviceDriver ==
"cob_ledboard")
187 else if(_deviceDriver ==
"ms-35")
189 else if(_deviceDriver ==
"stageprofi")
193 ROS_ERROR_STREAM(
"Unsupported devicedriver ["<<_deviceDriver<<
"], falling back to sim mode");
196 status.message =
"Unsupported devicedriver. Running in simulation mode";
202 status.message =
"Initializing connection to driver failed";
203 ROS_ERROR(
"Initializing connection to driver failed. Exiting");
209 ROS_WARN(
"Serial connection on %s failed.", _deviceString.c_str());
210 ROS_WARN(
"Simulation mode enabled");
215 status.message =
"Serial connection failed. Running in simulation mode";
220 ROS_INFO(
"Simulation mode enabled");
221 if(_deviceDriver ==
"markers")
232 status.message =
"light controller running in simulation";
271 boost::mutex::scoped_lock lock(
_mutex);
275 if(color.colors.size() > 0)
277 if(color.colors.size() > 1)
281 std::vector<color::rgba> colors;
282 for(
size_t i=0; i<color.colors.size();i++)
284 if(color.colors[i].r <= 1.0 && color.colors[i].g <= 1.0 && color.colors[i].b <= 1.0)
293 ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
302 if(color.colors[0].r <= 1.0 && color.colors[0].g <= 1.0 && color.colors[0].b <= 1.0)
312 ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
320 bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
322 boost::mutex::scoped_lock lock(
_mutex);
327 if(req.mode.colors.size() > 0)
329 if(req.mode.colors[0].r > 1.0 || req.mode.colors[0].g > 1.0 ||
330 req.mode.colors[0].b > 1.0 || req.mode.colors[0].a > 1.0)
335 ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
337 else if(req.mode.mode == cob_light::LightModes::NONE)
361 boost::mutex::scoped_lock lock(
_mutex);
362 cob_light::SetLightModeResult result;
363 if(goal->mode.colors.size() > 0)
365 if(goal->mode.colors[0].r > 1.0 || goal->mode.colors[0].g > 1.0 ||
366 goal->mode.colors[0].b > 1.0 || goal->mode.colors[0].a > 1.0)
370 result.track_id = -1;
371 _as->
setAborted(result,
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
373 ROS_ERROR(
"Unsupported Color format. rgba values range is between 0.0 - 1.0");
375 else if(goal->mode.mode == cob_light::LightModes::NONE)
382 result.track_id = -1;
390 result.track_id = u_id;
398 bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
400 boost::mutex::scoped_lock lock(
_mutex);
418 visualization_msgs::Marker marker;
423 marker.type = visualization_msgs::Marker::SPHERE;
424 marker.action = visualization_msgs::Marker::ADD;
425 marker.pose.position.x = 0.5;
426 marker.pose.position.y = 0.0;
427 marker.pose.position.z = 0.0;
428 marker.pose.orientation.x = 0.0;
429 marker.pose.orientation.y = 0.0;
430 marker.pose.orientation.z = 0.0;
431 marker.pose.orientation.w = 1.0;
432 marker.scale.x = 0.1;
433 marker.scale.y = 0.1;
434 marker.scale.z = 0.1;
435 marker.color.a = color.
a;
436 marker.color.r = color.
r;
437 marker.color.g = color.
g;
438 marker.color.b = color.
b;
477 int main(
int argc,
char** argv)
489 if(lightControl->
init())
void setNumLeds(size_t num_leds)
bool stopMode(cob_light::StopLightMode::Request &req, cob_light::StopLightMode::Response &res)
void actionCallback(const cob_light::SetLightModeGoalConstPtr &goal)
std::string _sMarkerFrame
int openPort(std::string devicestring, int baudrate)
ros::Publisher _pubDiagnostic
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void topicCallback(cob_light::ColorRGBAArray color)
void shutdownCallback(XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
boost::signals2::signal< void(color::rgba color)> * signalColorSet()
void publish_diagnostics_cb(const ros::TimerEvent &)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sig_atomic_t volatile gShutdownRequest
ROSCPP_DECL const std::string & getName()
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
ros::Publisher _pubMarker
int getExecutingPriority()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Type const & getType() const
void publish(const boost::shared_ptr< M > &message) const
ros::ServiceServer _srvServer
bool getParam(const std::string &key, std::string &s) const
ros::Subscriber _sub_mode
void markerCallback(color::rgba color)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool hasParam(const std::string &key) const
uint64_t execute(boost::shared_ptr< Mode > mode)
ModeExecutor * p_modeExecutor
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
ros::ServiceServer _srvStopMode
diagnostic_msgs::DiagnosticArray _diagnostics
virtual void setColorMulti(std::vector< color::rgba > &colors)=0
static const XMLRPCManagerPtr & instance()
ROSCPP_DECL void shutdown()
actionlib::SimpleActionServer< cob_light::SetLightModeAction > ActionServer
ros::Timer _diagnostics_timer
uint64_t getExecutingUId()
virtual void setColor(color::rgba color)=0
#define ROS_ERROR_STREAM(args)
void sigIntHandler(int signal)
std::string _deviceString
bool serviceCallback(cob_light::SetLightMode::Request &req, cob_light::SetLightMode::Response &res)
std::string _deviceDriver
static boost::shared_ptr< Mode > create(cob_light::LightMode requestMode, IColorO *colorO)