#include <sr_publisher.h>
Public Member Functions | |
void | publish () |
SRPublisher (boost::shared_ptr< SRArticulatedRobot > sr_art_robot) | |
~SRPublisher () | |
Destructor. | |
Private Member Functions | |
double | toRad (double deg) |
Private Attributes | |
NodeHandle | n_tilde |
NodeHandle | node |
ros node handle | |
Rate | publish_rate |
the rate at which the data will be published. This can be set by a parameter in the launch file. | |
boost::shared_ptr < SRArticulatedRobot > | sr_articulated_robot |
The shadowhand object (can be either an object connected to the real robot or a virtual hand). | |
Publisher | sr_jointstate_pos_pub |
The publisher which publishes the data to the \/{prefix}\/position\/joint_states topic. | |
Publisher | sr_jointstate_target_pub |
The publisher which publishes the data to the \/{prefix}\/target\/joint_states topic. | |
Publisher | sr_pub |
The publisher which publishes the data to the \/{prefix}\/shadowhand_data topic. |
This class publishes data concerning the shadowhand /shadowarm, like position, targets, forces, ... on different topics. To publish those data, just call the publish() function.
The data are published on three different topics. Two of them are joint_states topics (joint names, joint angles, joint velocities, joint efforts), which are then transformed into coordinates by two different robot_state_publisher (a ROS package). This is useful to visualize the data in rviz (part of ROS). A third topic is \/prefix\/shadowhand_data. The messages published on this last topic are better formatted for our hardware.
Definition at line 51 of file sr_publisher.h.
shadowrobot::SRPublisher::SRPublisher | ( | boost::shared_ptr< SRArticulatedRobot > | sr_art_robot | ) |
Constructor initializing the ROS node, and setting the topic to which it publishes. The frequency at which this node will publish data is set by a parameter, read from ROS parameter server.
sr_art_robot | A Shadowhand or Shadowarm object, where the information to be published comes from. |
Definition at line 53 of file sr_publisher.cpp.
Destructor.
Definition at line 78 of file sr_publisher.cpp.
void shadowrobot::SRPublisher::publish | ( | ) |
The callback method which is called at a given frequency. Gets the data from the shadowhand/shadowarm object.
Definition at line 87 of file sr_publisher.cpp.
double shadowrobot::SRPublisher::toRad | ( | double | deg | ) | [inline, private] |
Convert an angle in degree to an angle in radians.
deg | the angle in degrees |
Definition at line 91 of file sr_publisher.h.
NodeHandle shadowrobot::SRPublisher::n_tilde [private] |
Definition at line 72 of file sr_publisher.h.
NodeHandle shadowrobot::SRPublisher::node [private] |
ros node handle
Definition at line 72 of file sr_publisher.h.
Rate shadowrobot::SRPublisher::publish_rate [private] |
the rate at which the data will be published. This can be set by a parameter in the launch file.
Definition at line 74 of file sr_publisher.h.
boost::shared_ptr<SRArticulatedRobot> shadowrobot::SRPublisher::sr_articulated_robot [private] |
The shadowhand object (can be either an object connected to the real robot or a virtual hand).
Definition at line 77 of file sr_publisher.h.
The publisher which publishes the data to the \/{prefix}\/position\/joint_states topic.
Definition at line 80 of file sr_publisher.h.
The publisher which publishes the data to the \/{prefix}\/target\/joint_states topic.
Definition at line 82 of file sr_publisher.h.
Publisher shadowrobot::SRPublisher::sr_pub [private] |
The publisher which publishes the data to the \/{prefix}\/shadowhand_data topic.
Definition at line 84 of file sr_publisher.h.