hardware_interface Documentation

hardware_interface

Hardware Interface base class.

Hardware interfaces are used by ROS control in conjunction with one of the available ROS controllers to send (hardware_interface::RobotHW::write) commands to the hardware and receive (hardware_interface::RobotHW::read) states from the robot's resources (joints, sensors, actuators).

A list of available hardware interfaces (provided via the HardwareResourceManager) as of this writing are:

Note that hardware_interface::JointCommandInterface allows both reading joint state and commanding [effort|velocity|position]-based joints (see this answer).

Setting up a new robot

The following example explains how to set up a new robot to work with the controller_manager. When you make your robot support one or more of the standard interfaces, you will be able to take advantage of a large library of controllers (see ros_controllers) that work on the standard interfaces mentioned above.

hw_interface_2.png

As the image above suggests, a custom robot hardware interface is not limited to be composed of only one single interface. The robot can provide as many interfaces as required. It could for example provide both the hardware_interface::PositionJointInterface and the hardware_interface::VelocityJointInterface, and many more.

Assuming a robot with two joints: A & B where both joints are position controlled. Such a robot is defined with a class derived from hardware_interface::RobotHW that should provide the standard PositionJointInterface and the JointStateInterface, so it can re-use all controllers that are already written to work with the PositionJointInterface and the JointStateInterface. The code would look like this:

class MyRobot : public hardware_interface::RobotHW
{
public:
MyRobot()
{
// Initialization of the robot's resources (joints, sensors, actuators) and
// interfaces can be done here or inside init().
// E.g. parse the URDF for joint names & interfaces, then initialize them
}
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)
{
// Create a JointStateHandle for each joint and register them with the
// JointStateInterface.
hardware_interface::JointStateHandle state_handle_a("A", &pos[0], &vel[0], &eff[0]);
jnt_state_interface.registerHandle(state_handle_a);
hardware_interface::JointStateHandle state_handle_b("B", &pos[1], &vel[1], &eff[1]);
jnt_state_interface.registerHandle(state_handle_b);
// Register the JointStateInterface containing the read only joints
// with this robot's hardware_interface::RobotHW.
registerInterface(&jnt_state_interface);
// Create a JointHandle (read and write) for each controllable joint
// using the read-only joint handles within the JointStateInterface and
// register them with the JointPositionInterface.
hardware_interface::JointHandle pos_handle_a(jnt_state_interface.getHandle("A"), &cmd[0]);
jnt_pos_interface.registerHandle(pos_handle_a);
hardware_interface::JointHandle pos_handle_b(jnt_state_interface.getHandle("B"), &cmd[1]);
jnt_pos_interface.registerHandle(pos_handle_b);
// Register the JointPositionInterface containing the read/write joints
// with this robot's hardware_interface::RobotHW.
registerInterface(&jnt_pos_interface);
return true;
}
private:
// hardware_interface::JointStateInterface gives read access to all joint values
// without conflicting with other controllers.
// hardware_interface::PositionJointInterface inherits from
// hardware_interface::JointCommandInterface and is used for reading and writing
// joint positions. Because this interface reserves the joints for write access,
// conflicts with other controllers writing to the same joints might occure.
// To only read joint positions, avoid conflicts using
// hardware_interface::JointStateInterface.
// Data member array to store the controller commands which are sent to the
// robot's resources (joints, actuators)
double cmd[2];
// Data member arrays to store the state of the robot's resources (joints, sensors)
double pos[2];
double vel[2];
double eff[2];
};

This code represents a custom robot and is required to control it. The functions above are designed to give the controller manager (and the controllers inside the controller manager) access to the joint state of custom robot, and to command it. When the controller manager runs, the controllers will read from the pos, vel and eff variables of the custom robot hardware interface, and the controller will write the desired command into the cmd variable. It's mandatory to make sure the pos, vel and eff variables always have the latest joint state available, and to make sure that whatever is written into the cmd variable gets executed by the robot. This can be done by implementing hardware_interface::RobotHW::read() and a hardware_interface::RobotHW::write() methods. A node's main() function can be implemented like this:

#include <ros/ros.h>
#include <my_robot/my_robot.h>
#include <controller_manager/controller_manager.h>
int main(int argc, char **argv)
{
// Initialize the ROS node
ros::init(argc, argv, "my_robot");
// Create an instance of your robot so that this instance knows about all
// the resources that are available.
MyRobot::MyRobot robot;
// Create an instance of the controller manager and pass it the robot,
// so that it can handle its resources.
controller_manager::ControllerManager cm(&robot);
// Setup a separate thread that will be used to service ROS callbacks.
ros:AsyncSpinner spinner(1);
spinner.start();
// Setup for the control loop.
ros::Time prev_time = ros::Time::now();
ros::Rate rate(10.0); // 10 Hz rate
while (ros::ok())
{
// Basic bookkeeping to get the system time in order to compute the control period.
const ros::Time time = ros:Time::now();
const ros::Duration period = time - prev_time;
prev_time = time;
// Execution of the actual control loop.
robot.read();
// If needed, its possible to define transmissions in software by calling the
// transmission_interface::ActuatorToJointPositionInterface::propagate()
// after reading the joint states.
cm.update(time, period);
// In case of software transmissions, use
// transmission_interface::JointToActuatorEffortHandle::propagate()
// to convert from the joint space to the actuator space.
root.write();
// All these steps keep getting repeated with the specified rate.
rate.sleep();
}
return 0;
}

To implement software transmissions, see transmission_interface for examples.

Resource Management

The controller manager keeps track of which resources are in use by each of the controllers. A resource can be something like 'right_elbow_joint', 'base', 'left_arm', 'wrist_joints'. Pretty much anything a specific robot can consist of. Put simply, resources are specified in the robot's hardware interface (derived from hardware_interface::RobotHW). And a robot is represented by a bunch of hardware interfaces, where one is a set of similar resources. For example, the hardware_interface::PositionJointInterface groups the position controlled joints as resources. It is also possible to implement a custom hardware interface, and define custom resources. When controllers are getting initialized, they request a number of resources from the hardware interface; these requests get recorded by the controller manager. So the controller manager knows exactly which controller has requested which resources.

The RobotHW class has a simple default implementation for resource management: it simply prevents two controllers that are using the same resource to be running at the same time. Note that two controllers that are using the same resource can be loaded at the same time, but can't be running at the same time. If this simple resource management scheme fits to a robot, nothing else needs to be done, the controller manager will automatically apply this scheme. If a robot needs a different scheme, it is possible to create a custom one, by implementing one single function:

class MyRobot : public hardware_interface::RobotHW
{
public:
MyRobot()
{
// register hardware interfaces interfaces
...
... (see the code above)
...
// Implement robot-specific resouce management
bool checkForConflict(const std::list<ControllerInfo>& info) const
{
// This list of controllers cannot be running at the same time
...
return true;
// This list of controller can be running at the same time
...
return false;
}
}
};

The input to the hardware_interface::RobotHW::checkForConflict method is a list of controller info objects. Each of these objects matches to one single controller, and contains all the info about that controller. This info includes the controller name, controller type, hardware interface type, and the list of resources that are claimed by the controller. Based on all this info, it is possible to come up with a custom scheme to decide if the given list of controllers is allowed to be running at the same time.

Creating a robot-specific interface

The standard interfaces are helpful to avoid writing a whole new set of controllers for a robot, and to take advantage of the libraries of existing controllers. But in case a robot has some features that are not supported by the standard interfaces it is possible to leverage the standard interfaces (and re-use the standard controllers) for the features of a robot that are standard. And at the same time expose robot-specific features in a robot-specific interface. The image shown above shows a robot with both standard and robot-specific interfaces.

The code for such a robot looks like this:

class MyRobot : public hardware_interface::RobotHW
{
public:
MyRobot()
{
// Register the joint state and position interfaces.
...
... (see the code above)
...
// Register some robot specific interfaces.
registerInterface(&cool_interface);
}
private:
MyCustomInterface cool_interface;
};

Anotehr way is to register the MyRobot class itself:

{
public:
MyRobot()
{
// Register the joint state and position interfaces.
...
... (see the code above)
...
// Register the MyRobot class itself to make the 'someCoolFunction' available.
// The MyRobot class inherits from HardwareInterface to make this possible.
}
void someCoolFunction();
};

With this, the custom interfaces could be nothing more than adding any number of function calls to a custom robot class, and registering the robot class itself. These robot-specific functions will only be available to controllers that are specifically designed for the custom robot, but at the same time, the robot will still work with standard controllers using the standard interfaces of the robot.

ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
hardware_interface::JointStateInterface
Hardware interface to support reading the state of an array of joints.
Definition: joint_state_interface.h:230
ros
ros.h
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
Register an interface.
Definition: interface_manager.h:138
hardware_interface::HardwareInterface
Abstract Hardware Interface.
Definition: hardware_interface.h:46
hardware_interface::RobotHW::checkForConflict
virtual bool checkForConflict(const std::list< ControllerInfo > &info) const
Definition: robot_hw.h:113
hardware_interface::RobotHW::init
virtual bool init(ros::NodeHandle &, ros::NodeHandle &)
The init function is called to initialize the RobotHW from a non-realtime thread.
Definition: robot_hw.h:102
ros::ok
ROSCPP_DECL bool ok()
main
def main()
hardware_interface::RobotHW
Robot Hardware Interface and Resource Manager.
Definition: robot_hw.h:78
hardware_interface::JointStateHandle
A handle used to read the state of a single joint. Currently, position, velocity and effort fields ar...
Definition: joint_state_interface.h:45
hardware_interface::JointHandle
A handle used to read and command a single joint.
Definition: joint_command_interface.h:42
ros::Time
joint_state_interface.h
robot_hw.h
ros::Rate
joint_command_interface.h
hardware_interface::PositionJointInterface
JointCommandInterface for commanding position-based joints.
Definition: joint_command_interface.h:88
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:19