#include <effort_joint_interface_provider.h>
Public Member Functions | |
bool | updateJointInterfaces (const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map) |
Update a robot's joint interfaces with joint information contained in a transmission. | |
Protected Member Functions | |
bool | getActuatorCommandData (const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_cmd_data) |
bool | getJointCommandData (const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_cmd_data) |
bool | registerTransmission (TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data) |
Definition at line 41 of file effort_joint_interface_provider.h.
bool transmission_interface::EffortJointInterfaceProvider::getActuatorCommandData | ( | const TransmissionInfo & | transmission_info, |
hardware_interface::RobotHW * | robot_hw, | ||
ActuatorData & | act_cmd_data | ||
) | [protected, virtual] |
Reimplemented from transmission_interface::JointStateInterfaceProvider.
Definition at line 96 of file effort_joint_interface_provider.cpp.
bool transmission_interface::EffortJointInterfaceProvider::getJointCommandData | ( | const TransmissionInfo & | transmission_info, |
const RawJointDataMap & | raw_joint_data_map, | ||
JointData & | jnt_cmd_data | ||
) | [protected, virtual] |
Reimplemented from transmission_interface::JointStateInterfaceProvider.
Definition at line 75 of file effort_joint_interface_provider.cpp.
bool transmission_interface::EffortJointInterfaceProvider::registerTransmission | ( | TransmissionLoaderData & | loader_data, |
TransmissionHandleData & | handle_data | ||
) | [protected, virtual] |
Reimplemented from transmission_interface::JointStateInterfaceProvider.
Definition at line 121 of file effort_joint_interface_provider.cpp.
bool transmission_interface::EffortJointInterfaceProvider::updateJointInterfaces | ( | const TransmissionInfo & | transmission_info, |
hardware_interface::RobotHW * | robot_hw, | ||
JointInterfaces & | joint_interfaces, | ||
RawJointDataMap & | raw_joint_data_map | ||
) | [virtual] |
Update a robot's joint interfaces with joint information contained in a transmission.
[in] | transmission_info | Structure containing information of which joints to add. Only new, non-previously registered joints will be added. |
[out] | joint_ifaces | Joint interfaces where new joints will be added. It may already contain data, which will not be overwritten; only new joints will be added. |
raw_joint_data_map[out] | Structure where the raw data of new joints will reside. It may already contain data, which will not be overwritten; only new data will be added. |
Reimplemented from transmission_interface::JointStateInterfaceProvider.
Definition at line 38 of file effort_joint_interface_provider.cpp.