Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions
industrial_robot_client::joint_relay_handler::JointRelayHandler Class Reference

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

#include <joint_relay_handler.h>

Inheritance diagram for industrial_robot_client::joint_relay_handler::JointRelayHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool init (industrial::smpl_msg_connection::SmplMsgConnection *connection, std::vector< std::string > &joint_names)
 Class initializer.
 JointRelayHandler ()
 Constructor.

Protected Member Functions

virtual bool create_messages (JointMessage &msg_in, control_msgs::FollowJointTrajectoryFeedback *control_state, sensor_msgs::JointState *sensor_state)
 Convert joint message into publish message-types.
bool internalCB (JointMessage &in)
 Callback executed upon receiving a joint message.
virtual bool 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)
 Select specific joints for publishing.
virtual bool transform (const std::vector< double > &pos_in, std::vector< double > *pos_out)
 Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling.

Protected Attributes

std::vector< std::string > all_joint_names_
ros::NodeHandle node_
ros::Publisher pub_joint_control_state_
ros::Publisher pub_joint_sensor_state_

Private Member Functions

bool internalCB (SimpleMessage &in)
 Callback executed upon receiving a message.

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 61 of file joint_relay_handler.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 71 of file joint_relay_handler.h.


Member Function Documentation

bool industrial_robot_client::joint_relay_handler::JointRelayHandler::create_messages ( JointMessage msg_in,
control_msgs::FollowJointTrajectoryFeedback *  control_state,
sensor_msgs::JointState *  sensor_state 
) [protected, virtual]

Convert joint message into publish message-types.

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

Definition at line 98 of file joint_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)

Definition at line 46 of file joint_relay_handler.cpp.

Callback executed upon receiving a joint message.

Parameters:
inincoming message
Returns:
true on success, false otherwise

Definition at line 72 of file joint_relay_handler.cpp.

Callback executed upon receiving a message.

Parameters:
inincoming message
Returns:
true on success, false otherwise

Implements industrial::message_handler::MessageHandler.

Definition at line 59 of file joint_relay_handler.cpp.

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 
) [protected, virtual]

Select specific joints for publishing.

Parameters:
[in]all_joint_posjoint positions, in count/order matching robot connection
[in]all_joint_namesjoint names, matching all_joint_pos
[out]pub_joint_posjoint positions selected for publishing
[out]pub_joint_namesjoint names selected for publishing
Returns:
true on success, false otherwise

Definition at line 146 of file joint_relay_handler.cpp.

virtual bool industrial_robot_client::joint_relay_handler::JointRelayHandler::transform ( const std::vector< double > &  pos_in,
std::vector< double > *  pos_out 
) [inline, protected, virtual]

Transform joint positions before publishing. Can be overridden to implement, e.g. robot-specific joint coupling.

Parameters:
[in]pos_injoint positions, exactly as passed from robot connection.
[out]pos_outtransformed 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.


Member Data Documentation

Definition at line 88 of file joint_relay_handler.h.

Definition at line 92 of file joint_relay_handler.h.

Definition at line 90 of file joint_relay_handler.h.

Definition at line 91 of file joint_relay_handler.h.


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


industrial_robot_client
Author(s): Jeremy Zoss
autogenerated on Tue Jan 17 2017 21:10:11