Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
adept::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 adept::joint_relay_handler::JointRelayHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool init (industrial::smpl_msg_connection::SmplMsgConnection *connection)
 Class initializer.
bool init (int msg_type, industrial::smpl_msg_connection::SmplMsgConnection *connection)
 Class initializer (Direct call to base class with the same name) I couldn't get the "using" form to work/.
 JointRelayHandler (ros::NodeHandle &n)
 Constructor.

Private Member Functions

bool internalCB (industrial::simple_message::SimpleMessage &in)
 Callback executed upon receiving a ping message.

Private Attributes

control_msgs::FollowJointTrajectoryFeedback joint_control_state_
sensor_msgs::JointState joint_sensor_state_
ros::NodeHandle node_
ros::Publisher pub_joint_control_state_
ros::Publisher pub_joint_sensor_state_

Static Private Attributes

static const int NUM_OF_JOINTS_ = 6

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


Constructor & Destructor Documentation

Constructor.

Parameters:
ROSnode handle (used for publishing)

Definition at line 46 of file joint_relay_handler.cpp.


Member Function Documentation

Class initializer.

Parameters:
connectionsimple message connection that will be used to send replies.
Returns:
true on success, false otherwise (an invalid message type)

Definition at line 77 of file joint_relay_handler.cpp.

Class initializer (Direct call to base class with the same name) I couldn't get the "using" form to work/.

Parameters:
connectionsimple message connection that will be used to send replies.
Returns:
true on success, false otherwise (an invalid message type)

Reimplemented from industrial::message_handler::MessageHandler.

Definition at line 89 of file joint_relay_handler.h.

Callback executed upon receiving a ping message.

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

Implements industrial::message_handler::MessageHandler.

Definition at line 82 of file joint_relay_handler.cpp.


Member Data Documentation

control_msgs::FollowJointTrajectoryFeedback adept::joint_relay_handler::JointRelayHandler::joint_control_state_ [private]

Definition at line 90 of file joint_relay_handler.h.

Definition at line 97 of file joint_relay_handler.h.

Definition at line 100 of file joint_relay_handler.h.

Definition at line 102 of file joint_relay_handler.h.

Definition at line 98 of file joint_relay_handler.h.

Definition at line 99 of file joint_relay_handler.h.


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


adept_common
Author(s): root
autogenerated on Sun Oct 5 2014 22:05:33