[Documentation] [TitleIndex] [WordIndex

Only released in EOL distros:  

Overview

A simple example project that demonstrates how to create a custom driver using the actuator_array_driver base class. This example uses a simulated servo motor to demonstrate the driver operation while avoiding hardware dependencies.

For details on how to create your own Actuator Array Driver, see the tutorials page.

ROS Nodes

example1_driver

This is a very simple example demonstrating the use of the Actuator Array Driver base class. This example makes use of convinience classes provided in the base class to read a simple list of actuators from the parameter server and set up the standard Actuator Array Driver communication interface. This example does not make use of the robot description. Instead, the init_actuator_ function manually fills in some of the useful properties for each actuator. A Dummy Actuator class is used to simulate the operation of a real R/C Servo motor. This removes the need to have specific hardware to test the basic Actuator Array Driver system.

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)

Configuration Files

cfg/Example1Joints.yaml

Launch Files

launch/example1.launch

example2_driver

This example extends example1_driver to use the robot description file. Because the base class was designed to use the robot description information, there are very few code changes. The only different is the custom 'init_actuator_' function now makes use of information obtained from the robot description instead of using hard-coded defaults. The only extra work really involved is in the creation of the robot description file itself.

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)

Configuration Files

cfg/Example2Joints.yaml

robots/robot2.urdf.xacro

Launch Files

launch/example2.launch

example3_driver

In this example, a timer is used to trigger read events instead of the built-in spin() function. The YAML configuration file associated with Example3 provides additional properties, such as a channel number and home position for each servo. The custom 'init_actuator_' function demonstrates how to read these additional fields from the XMLRPS structure. Also, as a demonstration, the various helper functions are called directly, instead of using the all-in-one 'init()' function. Again, a Dummy Actuator class is used to simulate the operation of a real R/C Servo motor. This removes the need to have specific hardware to test the basic Actuator Array Driver system.

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)

Configuration Files

cfg/Example3Joints.yaml

robots/robot3.urdf.xacro

Launch Files

launch/example3.launch


2024-02-24 12:24