This class provides a Publisher implementation for use with kaco::Bridge and a CiA 402 motor device. It publishes the motor state as JointState messages from the ROS common_messages package. More...
#include <joint_state_publisher.h>
Public Member Functions | |
JointStatePublisher (Device &device, int32_t position_0_degree, int32_t position_360_degree, const std::string &position_actual_field="Position actual value", const std::string &topic_name="") | |
Constructor. More... | |
void | advertise () override |
void | publish () override |
This class provides a Publisher implementation for use with kaco::Bridge and a CiA 402 motor device. It publishes the motor state as JointState messages from the ROS common_messages package.
Currenty, only the motor angle is published. You have to initialize the motor on your own. The motor is expected to be in position mode.
Definition at line 51 of file joint_state_publisher.h.
kaco::JointStatePublisher::JointStatePublisher | ( | Device & | device, |
int32_t | position_0_degree, | ||
int32_t | position_360_degree, | ||
const std::string & | position_actual_field = "Position actual value" , |
||
const std::string & | topic_name = "" |
||
) |
Constructor.
device | a CiA 402 compliant motor device object |
position_0_degree | The motor position (dictionary entry "Position actual value") which represents a 0 degree angle. |
position_360_degree | Like position_0_degree for 360 degree state. |
position_actual_field | Name of the dictionary entry to use. |
topic_name | Custom topic name. Leave out for default. |
std::runtime_error | if device is not CiA 402 compliant and in position_mode. |
Definition at line 46 of file joint_state_publisher.cpp.
|
overridevirtual |
Implements kaco::Publisher.
Definition at line 76 of file joint_state_publisher.cpp.
|
overridevirtual |
Implements kaco::Publisher.
Definition at line 86 of file joint_state_publisher.cpp.