Public Member Functions | Protected Member Functions | Protected Attributes
actuator_array_driver::ActuatorArrayDriver< JOINT > Class Template Reference

#include <actuator_array_driver.h>

List of all members.

Public Member Functions

 ActuatorArrayDriver ()
void read_and_publish ()
 helper method that reads/updates the joint states, then publishes the joint state message This is used internally in spin(), but can also be used inside an external run loop
void spin ()
 helper method that puts the node into an infinite read-publish loop. This is a common practice for driver nodes. As an alternative to the spin() function, a timer may be set up to periodically call read_and_publish. This is up to the driver designer to decide.
virtual ~ActuatorArrayDriver ()

Protected Member Functions

void advertise_and_subscribe (ros::NodeHandle &node)
 helper method that sets up the communication elements with ROS. This involves subscribing to the 'command' topic, advertising the 'joint_states' topic, and creating the 'stop' and 'home' services. All topics will be advertised in the namespace of the provided 'node' object.
virtual bool command_ ()
 virtual function that handles sending a command to the device. This gets called once after every message received on the 'command' topic. The internal command_msg_ will already be updated with the new command information
void command_callback (const sensor_msgs::JointState::ConstPtr &command_msg)
 Callback performed upon receipt of a command. Copies the common joint information between the received command message and the current list of configured joints and stores it in command_msg_. The virtual function command_() is then called.
virtual bool home_ ()
 virtual function that sends the device to the home position. This gets called in response to a 'home' service call
bool home_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 ROS home service callback function. Simply calls the virtual home_() function.
void init ()
 convenience method that calls 'parse_actuator_list', 'parse_urdf' and 'advertise_and_subscribe' in order. This is broken out of the constructor to allow derived classes to choose how to initialize the system (e.g. Gazebo plugin). Most derived classes will probably want to call init() in the constructor.
virtual bool init_actuator_ (const std::string &joint_name, JOINT &joint_properties, XmlRpc::XmlRpcValue &joint_data)
 helper method that performs custom initialization on a per-actuator basis. If the 'joints' parameter contains an XMLRPC array of structs, then this function is also provided with the full XMLRPC structure. This is
void parse_actuator_list (const ros::NodeHandle &node)
 helper method that reads in a list of actuator names from the parameter server and initializes the joints_ map. This list can be a simple, comma-separated list loaded via rosparam, or a complex struct defining additional properties about each actuator. If the struct approach is used, generally loaded via a YAML file, one entry must be called 'name'. Additionally, an initialization function named 'init_actuator_' can be implemented. This function is called once per actuator in the list, and is provided with the full XMLRPC struct for that actuator. This call occurs after the joint is updated using the URDF information, so any information inside the URDF can be accessed by the initialization function. The provided node object should be in the namespace of the 'joints' list on the parameter server (i.e. a private node)
void parse_urdf (const ros::NodeHandle &node)
 helper method that parses the URDF contained in the robot_description_parameter on the Parameter Server and stores it in the urdf_model_ property of the base class.
virtual bool read_ (ros::Time ts=ros::Time::now())
 virtual function that is responsible for reading the current device state and updating the internal joint_state_msg_
virtual bool stop_ ()
 virtual function that sends a stop command to the device. This gets called in response to a 'stop' service call
bool stop_callback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 ROS stop service callback function. Simply calls the virtual stop_() function.
void update_joint_from_urdf (const std::string &joint_name, JOINT &joint_properties)
 helper method that extracts information from the URDF model about a specific joint name and stores it in the provided 'joint_properties' struct. If the provided joint name does not exist in the URDF, a warning will be issued and the 'joint_properties' struct will not be updated.

Protected Attributes

sensor_msgs::JointState command_msg_
 Holds a copy of the latest ROS command message for each joint.
ros::Subscriber command_sub_
 ROS command subscription.
ros::ServiceServer home_srv_
 ROS home service.
sensor_msgs::JointState joint_state_msg_
 ROS joint_state message.
ros::Publisher joint_state_pub_
 ROS joint_state publisher.
std::map< std::string, JOINT > joints_
 list of joints to be controlled, accessible by joint name
std::string robot_description_parameter_
 name of the parameter value that holds the robot description, not the robot description itself
ros::ServiceServer stop_srv_
 ROS stop service.
urdf::Model urdf_model_
 The URDF model parsed from the provided robot_description.

Detailed Description

template<class JOINT>
class actuator_array_driver::ActuatorArrayDriver< JOINT >

Definition at line 80 of file actuator_array_driver.h.


Constructor & Destructor Documentation

Definition at line 39 of file actuator_array_driver_impl.h.

template<class JOINT >
actuator_array_driver::ActuatorArrayDriver< JOINT >::~ActuatorArrayDriver ( ) [virtual]

Definition at line 46 of file actuator_array_driver_impl.h.


Member Function Documentation

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::advertise_and_subscribe ( ros::NodeHandle node) [protected]

helper method that sets up the communication elements with ROS. This involves subscribing to the 'command' topic, advertising the 'joint_states' topic, and creating the 'stop' and 'home' services. All topics will be advertised in the namespace of the provided 'node' object.

Definition at line 187 of file actuator_array_driver_impl.h.

template<class JOINT >
virtual bool actuator_array_driver::ActuatorArrayDriver< JOINT >::command_ ( ) [inline, protected, virtual]

virtual function that handles sending a command to the device. This gets called once after every message received on the 'command' topic. The internal command_msg_ will already be updated with the new command information

Definition at line 190 of file actuator_array_driver.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::command_callback ( const sensor_msgs::JointState::ConstPtr &  command_msg) [protected]

Callback performed upon receipt of a command. Copies the common joint information between the received command message and the current list of configured joints and stores it in command_msg_. The virtual function command_() is then called.

Definition at line 228 of file actuator_array_driver_impl.h.

template<class JOINT >
virtual bool actuator_array_driver::ActuatorArrayDriver< JOINT >::home_ ( ) [inline, protected, virtual]

virtual function that sends the device to the home position. This gets called in response to a 'home' service call

Definition at line 198 of file actuator_array_driver.h.

template<class JOINT >
bool actuator_array_driver::ActuatorArrayDriver< JOINT >::home_callback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

ROS home service callback function. Simply calls the virtual home_() function.

Definition at line 275 of file actuator_array_driver_impl.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::init ( ) [protected]

convenience method that calls 'parse_actuator_list', 'parse_urdf' and 'advertise_and_subscribe' in order. This is broken out of the constructor to allow derived classes to choose how to initialize the system (e.g. Gazebo plugin). Most derived classes will probably want to call init() in the constructor.

Definition at line 204 of file actuator_array_driver_impl.h.

template<class JOINT >
virtual bool actuator_array_driver::ActuatorArrayDriver< JOINT >::init_actuator_ ( const std::string &  joint_name,
JOINT &  joint_properties,
XmlRpc::XmlRpcValue joint_data 
) [inline, protected, virtual]

helper method that performs custom initialization on a per-actuator basis. If the 'joints' parameter contains an XMLRPC array of structs, then this function is also provided with the full XMLRPC structure. This is

initialize the list of actuators to control, and define custom properties about each actuator. Such entries as 'channel id', 'offset' , and 'home' are common attributes that are unique to each actuator.

Definition at line 181 of file actuator_array_driver.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::parse_actuator_list ( const ros::NodeHandle node) [protected]

helper method that reads in a list of actuator names from the parameter server and initializes the joints_ map. This list can be a simple, comma-separated list loaded via rosparam, or a complex struct defining additional properties about each actuator. If the struct approach is used, generally loaded via a YAML file, one entry must be called 'name'. Additionally, an initialization function named 'init_actuator_' can be implemented. This function is called once per actuator in the list, and is provided with the full XMLRPC struct for that actuator. This call occurs after the joint is updated using the URDF information, so any information inside the URDF can be accessed by the initialization function. The provided node object should be in the namespace of the 'joints' list on the parameter server (i.e. a private node)

Definition at line 120 of file actuator_array_driver_impl.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::parse_urdf ( const ros::NodeHandle node) [protected]

helper method that parses the URDF contained in the robot_description_parameter on the Parameter Server and stores it in the urdf_model_ property of the base class.

Definition at line 75 of file actuator_array_driver_impl.h.

template<class JOINT >
virtual bool actuator_array_driver::ActuatorArrayDriver< JOINT >::read_ ( ros::Time  ts = ros::Time::now()) [inline, protected, virtual]

virtual function that is responsible for reading the current device state and updating the internal joint_state_msg_

Definition at line 185 of file actuator_array_driver.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::read_and_publish ( )

helper method that reads/updates the joint states, then publishes the joint state message This is used internally in spin(), but can also be used inside an external run loop

Definition at line 53 of file actuator_array_driver_impl.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::spin ( )

helper method that puts the node into an infinite read-publish loop. This is a common practice for driver nodes. As an alternative to the spin() function, a timer may be set up to periodically call read_and_publish. This is up to the driver designer to decide.

Definition at line 63 of file actuator_array_driver_impl.h.

template<class JOINT >
virtual bool actuator_array_driver::ActuatorArrayDriver< JOINT >::stop_ ( ) [inline, protected, virtual]

virtual function that sends a stop command to the device. This gets called in response to a 'stop' service call

Definition at line 194 of file actuator_array_driver.h.

template<class JOINT >
bool actuator_array_driver::ActuatorArrayDriver< JOINT >::stop_callback ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

ROS stop service callback function. Simply calls the virtual stop_() function.

Definition at line 268 of file actuator_array_driver_impl.h.

template<class JOINT >
void actuator_array_driver::ActuatorArrayDriver< JOINT >::update_joint_from_urdf ( const std::string &  joint_name,
JOINT &  joint_properties 
) [protected]

helper method that extracts information from the URDF model about a specific joint name and stores it in the provided 'joint_properties' struct. If the provided joint name does not exist in the URDF, a warning will be issued and the 'joint_properties' struct will not be updated.

Definition at line 90 of file actuator_array_driver_impl.h.


Member Data Documentation

template<class JOINT >
sensor_msgs::JointState actuator_array_driver::ActuatorArrayDriver< JOINT >::command_msg_ [protected]

Holds a copy of the latest ROS command message for each joint.

Definition at line 101 of file actuator_array_driver.h.

template<class JOINT >
ros::Subscriber actuator_array_driver::ActuatorArrayDriver< JOINT >::command_sub_ [protected]

ROS command subscription.

Definition at line 98 of file actuator_array_driver.h.

template<class JOINT >
ros::ServiceServer actuator_array_driver::ActuatorArrayDriver< JOINT >::home_srv_ [protected]

ROS home service.

Definition at line 115 of file actuator_array_driver.h.

template<class JOINT >
sensor_msgs::JointState actuator_array_driver::ActuatorArrayDriver< JOINT >::joint_state_msg_ [protected]

ROS joint_state message.

Definition at line 124 of file actuator_array_driver.h.

template<class JOINT >
ros::Publisher actuator_array_driver::ActuatorArrayDriver< JOINT >::joint_state_pub_ [protected]

ROS joint_state publisher.

Definition at line 121 of file actuator_array_driver.h.

template<class JOINT >
std::map<std::string, JOINT> actuator_array_driver::ActuatorArrayDriver< JOINT >::joints_ [protected]

list of joints to be controlled, accessible by joint name

Definition at line 134 of file actuator_array_driver.h.

template<class JOINT >
std::string actuator_array_driver::ActuatorArrayDriver< JOINT >::robot_description_parameter_ [protected]

name of the parameter value that holds the robot description, not the robot description itself

Definition at line 128 of file actuator_array_driver.h.

template<class JOINT >
ros::ServiceServer actuator_array_driver::ActuatorArrayDriver< JOINT >::stop_srv_ [protected]

ROS stop service.

Definition at line 109 of file actuator_array_driver.h.

template<class JOINT >
urdf::Model actuator_array_driver::ActuatorArrayDriver< JOINT >::urdf_model_ [protected]

The URDF model parsed from the provided robot_description.

Definition at line 131 of file actuator_array_driver.h.


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


actuator_array_driver
Author(s): Stephen Williams
autogenerated on Wed Nov 27 2013 12:00:24