Message handler that relays joint positions (converts simple message types to ROS message types and publishes them)
More...
#include <joint_relay_handler.h>
Message handler that relays joint positions (converts simple message types to ROS message types and publishes them)
THIS CLASS IS NOT THREAD-SAFE
Definition at line 61 of file joint_relay_handler.h.
◆ JointRelayHandler()
industrial_robot_client::joint_relay_handler::JointRelayHandler::JointRelayHandler |
( |
| ) |
|
|
inline |
◆ create_messages()
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::create_messages |
( |
JointMessage & |
msg_in, |
|
|
control_msgs::FollowJointTrajectoryFeedback * |
control_state, |
|
|
sensor_msgs::JointState * |
sensor_state |
|
) |
| |
|
protectedvirtual |
Convert joint message into publish message-types.
- Parameters
-
[in] | msg_in | Joint message from robot connection |
[out] | control_state | FollowJointTrajectoryFeedback message for ROS publishing |
[out] | sensor_state | JointState message for ROS publishing |
- Returns
- true on success, false otherwise
Definition at line 98 of file joint_relay_handler.cpp.
◆ init()
Class initializer.
- Parameters
-
connection | simple message connection that will be used to send replies. |
joint_names | list of joint-names for msg-publishing.
- Count and order should match data from robot connection.
- Use blank-name to exclude a joint from publishing.
|
- Returns
- true on success, false otherwise (an invalid message type)
Definition at line 46 of file joint_relay_handler.cpp.
◆ internalCB() [1/2]
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::internalCB |
( |
JointMessage & |
in | ) |
|
|
protected |
Callback executed upon receiving a joint message.
- Parameters
-
- Returns
- true on success, false otherwise
Definition at line 72 of file joint_relay_handler.cpp.
◆ internalCB() [2/2]
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::internalCB |
( |
SimpleMessage & |
in | ) |
|
|
privatevirtual |
◆ select()
bool industrial_robot_client::joint_relay_handler::JointRelayHandler::select |
( |
const std::vector< double > & |
all_joint_pos, |
|
|
const std::vector< std::string > & |
all_joint_names, |
|
|
std::vector< double > * |
pub_joint_pos, |
|
|
std::vector< std::string > * |
pub_joint_names |
|
) |
| |
|
protectedvirtual |
Select specific joints for publishing.
- Parameters
-
[in] | all_joint_pos | joint positions, in count/order matching robot connection |
[in] | all_joint_names | joint names, matching all_joint_pos |
[out] | pub_joint_pos | joint positions selected for publishing |
[out] | pub_joint_names | joint names selected for publishing |
- Returns
- true on success, false otherwise
Definition at line 146 of file joint_relay_handler.cpp.
◆ transform()
virtual bool industrial_robot_client::joint_relay_handler::JointRelayHandler::transform |
( |
const std::vector< double > & |
pos_in, |
|
|
std::vector< double > * |
pos_out |
|
) |
| |
|
inlineprotectedvirtual |
Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling.
- Parameters
-
[in] | pos_in | joint positions, exactly as passed from robot connection. |
[out] | pos_out | transformed joint positions (in same order/count as input positions) |
- Returns
- true on success, false otherwise
Definition at line 116 of file joint_relay_handler.h.
◆ all_joint_names_
std::vector<std::string> industrial_robot_client::joint_relay_handler::JointRelayHandler::all_joint_names_ |
|
protected |
◆ node_
ros::NodeHandle industrial_robot_client::joint_relay_handler::JointRelayHandler::node_ |
|
protected |
◆ pub_joint_control_state_
ros::Publisher industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_control_state_ |
|
protected |
◆ pub_joint_sensor_state_
ros::Publisher industrial_robot_client::joint_relay_handler::JointRelayHandler::pub_joint_sensor_state_ |
|
protected |
The documentation for this class was generated from the following files: