[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

actuator_array: actuator_array_driver | actuator_array_example | actuator_array_gazebo_plugin | actuator_array_gui

Package Summary

This package contains a base class for an Actuator Array Driver. This is intended for use with chains of R/C Servos or other similar devices where position (and velocity) commands are sent at irregular intervals, as opposed to the tight, real-time control loop of the PR2 Controller Manager system.

This base class performs some standard functionality, such as parsing joint limits out of the robot_description, subscribing to a 'command' topic, publishing on the 'joint_states' topic, and setting up a 'stop' and 'home' service call. This is designed to work as a stand-alone driver for controlling/tele-operating a chain of servos, or in conjunction with the Actuator Array Joint Trajectory Action. However, this is provided as a convenience only, and is not required for successful operation with the Actuator Array Joint Trajectory Action.

Overview

A base class that implements the common Actuator Array interface. This base class handles the communication with ROS and parses the robot description URDF for relevant information about the controlled joints. A custom driver that adheres to the Actuator Array protocol can be created by implementing just a few functions.

ROS Nodes

actuator_array_driver

The actuator_array_driver is actually a base class and not a node itself. However, the base class implements the following ROS API, so all derived nodes will also implement this API. Further, all nodes in the actuator_array stack assume this API.

Subscribed Topics

command (sensor_msgs/JointState)

Published Topics

joint_states (sensor_msgs/JointState)

Services

stop (std_srvs/Empty)

home (std_srvs/Empty)

Parameters

robot_description_parameter (string, default: robot_description)

joints (string)

C++ Interface

For a complete listing of all functions, see the C++ API reference. The actuator_array_driver driver is a base class for generating that custom drivers that interact with chains of r/c-type servos with minimal effort. By uses this base class, much of the ROS interface code is handled automatically and interoperability with the other nodes in the actuator_array stack is guaranteed.

The base class is templated on a JOINT structure. If no additional data is needed, the provided JointProperties can be used as the template argument. If additional information needs to be stored on a per-joint basis, then the JointProperties class can be used as a base for a custom JOINT structure.

Joint Properties

The standard JointProperties class contains the following entries. Additional entries can be created by deriving a custom JointProperties class using this as a base. This custom JOINT structure would then be provided as a template argument to the actuator_array_driver.

Required Functions

Because the specifics of the hardware to be controlled will vary between applications, the base class provides hooks for the end-user to implement the actual code nessisary to control the actuators. A default, empty implementation of each of these functions exist in case certain functionality is not requird.

bool init_actuator_(const std::string& joint_name, JOINT& joint_properties,         XmlRpc::XmlRpcValue& joint_data)

bool read_(ros::Time ts = ros::Time::now())

bool command_()

bool stop_()

bool home_()

Provided Convenience Functions

void parse_urdf(const ros::NodeHandle& node)

void update_joint_from_urdf(const std::string& joint_name, JOINT& joint_properties)

void parse_actuator_list(const ros::NodeHandle& node)

void advertise_and_subscribe(ros::NodeHandle& node)

void init()


2024-02-24 12:24