Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions
industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler Class Reference

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

#include <joint_feedback_relay_handler.h>

Inheritance diagram for industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool init (SmplMsgConnection *connection, std::vector< std::string > &joint_names)
 Class initializer.
 JointFeedbackRelayHandler (int robot_id=-1)
 Constructor.

Protected Member Functions

virtual bool convert_message (SimpleMessage &msg_in, JointTrajectoryPoint *joint_state)
 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.

Protected Attributes

int robot_id_

Private Member Functions

bool convert_message (JointFeedbackMessage &msg_in, JointTrajectoryPoint *joint_state)
 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)

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 57 of file joint_feedback_relay_handler.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 65 of file joint_feedback_relay_handler.h.


Member Function Documentation

bool industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler::convert_message ( SimpleMessage msg_in,
JointTrajectoryPoint *  joint_state 
) [protected, virtual]

Convert joint message into intermediate message-type.

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

Reimplemented from industrial_robot_client::joint_relay_handler::JointRelayHandler.

Definition at line 73 of file joint_feedback_relay_handler.cpp.

Convert joint feedback message into intermediate message-type.

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

Definition at line 104 of file joint_feedback_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler::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 57 of file joint_feedback_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler::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 44 of file joint_feedback_relay_handler.cpp.

bool industrial_robot_client::joint_feedback_relay_handler::JointFeedbackRelayHandler::JointDataToVector ( const industrial::joint_data::JointData joints,
std::vector< double > &  vec,
int  len 
) [static, private]

Definition at line 86 of file joint_feedback_relay_handler.cpp.


Member Data Documentation

Definition at line 82 of file joint_feedback_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 Wed Aug 26 2015 12:37:34