23 #ifndef __PLUGINS_ROBOTINO_ROS_JOINTS_THREAD_H_
24 #define __PLUGINS_ROBOTINO_ROS_JOINTS_THREAD_H_
26 #include <core/threading/thread.h>
27 #include <aspect/blocked_timing.h>
28 #include <aspect/logging.h>
29 #include <aspect/configurable.h>
30 #include <aspect/blackboard.h>
31 #include <plugins/ros/aspect/ros.h>
33 #include <ros/publisher.h>
34 #include <sensor_msgs/JointState.h>
37 class RobotinoSensorInterface;
55 protected:
virtual void run() { Thread::run(); }
60 ros::Publisher pub_joints_;
61 sensor_msgs::JointState joint_state_msg_;
virtual void run()
Stub to see name in backtrace for easier debugging.
Thread aspect to access to BlackBoard.
Thread aspect to get access to a ROS node handle.
Robotino IR distances as point cloud.
Thread class encapsulation of pthreads.
RobotinoRosJointsThread()
Constructor.
RobotinoSensorInterface Fawkes BlackBoard Interface.
virtual void loop()
Code to execute in the thread.
Thread aspect to use blocked timing.
virtual void finalize()
Finalize the thread.
Thread aspect to log output.
virtual void init()
Initialize the thread.