This class provides a Subscriber implementation for use with kaco::Bridge and a CiA 402 motor device. It listens for JointState messages from ROS common_messages package and updates the motor device accordingly. More...
#include <joint_state_subscriber.h>
Public Member Functions | |
JointStateSubscriber (Device &device, int32_t position_0_degree, int32_t position_360_degree, std::string topic_name="") | |
Constructor. More... | |
void | advertise () override |
This class provides a Subscriber implementation for use with kaco::Bridge and a CiA 402 motor device. It listens for JointState messages from ROS common_messages package and updates the motor device accordingly.
Currenty, only the motor angle is regarded. You have to initialize the motor on your own. The motor is expected to be in position mode and operational state.
Definition at line 54 of file joint_state_subscriber.h.
kaco::JointStateSubscriber::JointStateSubscriber | ( | Device & | device, |
int32_t | position_0_degree, | ||
int32_t | position_360_degree, | ||
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. |
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 44 of file joint_state_subscriber.cpp.
|
overridevirtual |
Implements kaco::Subscriber.
Definition at line 74 of file joint_state_subscriber.cpp.