Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes
industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler Class Reference

Message handler that relays joint positions (converts simple message types to ROS message types and publishes them) More...

#include <joint_feedback_ex_relay_handler.h>

Inheritance diagram for industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool init (SmplMsgConnection *connection, std::vector< std::string > &joint_names)
 Class initializer.
virtual bool init (SmplMsgConnection *connection, std::map< int, RobotGroup > &robot_groups)
 Class initializer.
 JointFeedbackExRelayHandler (int groups_number=-1)
 Constructor.

Protected Member Functions

virtual bool convert_message (JointFeedbackMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id)
 Convert joint message into intermediate message-type.
bool create_messages (SimpleMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
 Convert joint message into publish message-types.
bool create_messages (JointFeedbackMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state, int robot_id)

Protected Attributes

ros::Publisher dynamic_pub_joint_control_state_
int groups_number_
ros::Publisher pub_joint_control_state_
ros::Publisher pub_joint_sensor_state_
bool version_0_

Private Member Functions

bool convert_message (JointFeedbackExMessage &msg_in, DynamicJointsGroup *joint_state, int robot_id)
 Convert joint feedback message into intermediate message-type.

Static Private Member Functions

static bool JointDataToVector (const industrial::joint_data::JointData &joints, std::vector< double > &vec, int len)

Private Attributes

industrial::shared_types::shared_int valid_fields_from_message_
 bit-mask of (optional) fields that have been initialized with valid data

Detailed Description

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 68 of file joint_feedback_ex_relay_handler.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 74 of file joint_feedback_ex_relay_handler.h.


Member Function Documentation

bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::convert_message ( JointFeedbackMessage msg_in,
DynamicJointsGroup *  joint_state,
int  robot_id 
) [protected, virtual]

Convert joint message into intermediate message-type.

Parameters:
[in]msg_inMessage from robot connection
[out]joint_stateJointTrajectoryPt message for intermediate processing

Definition at line 162 of file joint_feedback_ex_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::convert_message ( JointFeedbackExMessage msg_in,
DynamicJointsGroup *  joint_state,
int  robot_id 
) [private]

Convert joint feedback message into intermediate message-type.

Parameters:
[in]msg_inJointFeedbackMessage from robot connection
[out]joint_stateJointTrajectoryPt message for intermediate processing
bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::create_messages ( SimpleMessage msg_in,
control_msgs::FollowJointTrajectoryFeedback *  control_state,
sensor_msgs::JointState *  sensor_state 
) [protected, virtual]

Convert joint message into publish message-types.

Parameters:
[in]msg_inMessage from robot connection
[out]control_stateFollowJointTrajectoryFeedback message for ROS publishing
[out]sensor_stateJointState message for ROS publishing
Returns:
true on success, false otherwise

Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.

Definition at line 83 of file joint_feedback_ex_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::create_messages ( JointFeedbackMessage msg_in,
control_msgs::FollowJointTrajectoryFeedback *  control_state,
sensor_msgs::JointState *  sensor_state,
int  robot_id 
) [protected]

Definition at line 111 of file joint_feedback_ex_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_ex_relay_handler::JointFeedbackExRelayHandler::init ( SmplMsgConnection connection,
std::vector< std::string > &  joint_names 
) [virtual]

Class initializer.

Parameters:
connectionsimple message connection that will be used to send replies.
joint_nameslist 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)

Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.

Definition at line 71 of file joint_feedback_ex_relay_handler.cpp.

Class initializer.

Parameters:
connectionsimple message connection that will be used to send replies.
joint_nameslist 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)

Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.

Definition at line 51 of file joint_feedback_ex_relay_handler.cpp.

Definition at line 236 of file joint_feedback_ex_relay_handler.cpp.


Member Data Documentation

Definition at line 98 of file joint_feedback_ex_relay_handler.h.

Definition at line 94 of file joint_feedback_ex_relay_handler.h.

bit-mask of (optional) fields that have been initialized with valid data

See also:
enum ValidFieldTypes

Definition at line 131 of file joint_feedback_ex_relay_handler.h.

Definition at line 95 of file joint_feedback_ex_relay_handler.h.


The documentation for this class was generated from the following files:


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:58