Go to the documentation of this file.
75 double position = {std::numeric_limits<double>::quiet_NaN()};
76 double velocity = {std::numeric_limits<double>::quiet_NaN()};
77 double effort = {std::numeric_limits<double>::quiet_NaN()};
80 double effort_cmd = {std::numeric_limits<double>::quiet_NaN()};
185 template <
class Interface>
186 static bool hasResource(
const std::string& name,
const Interface& iface)
191 const std::vector<std::string>& existing_resources = iface.getNames();
192 if (existing_resources.end() != std::find(existing_resources.begin(), existing_resources.end(), name))
195 demangledTypeName<Interface>());
201 demangledTypeName<Interface>());
206 template <
class HardwareInterface,
class Handle>
209 std::vector<Handle>& handles)
215 HardwareInterface* hw_iface = robot_hw->
get<HardwareInterface>();
221 demangledTypeName<HardwareInterface>() <<
"'.");
226 for (
const auto& info : actuators_info)
230 handles.push_back(hw_iface->getHandle(info.name_));
232 catch(
const HardwareInterfaceException& ex)
235 "' does not expose the required hardware interface '" <<
236 demangledTypeName<HardwareInterface>() <<
"'.");
335 bool load(
const std::string& urdf);
345 bool load(
const std::vector<TransmissionInfo>& transmission_info_vec);
virtual bool updateJointInterfaces(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map)=0
Update a robot's joint interfaces with joint information contained in a transmission.
ActuatorToJointEffortInterface act_to_jnt_eff_cmd
std::shared_ptr< Transmission > TransmissionSharedPtr
ActuatorToJointVelocityInterface act_to_jnt_vel_cmd
Joint interfaces of a robot. Only used interfaces need to be populated.
ActuatorToJointStateInterface act_to_jnt_state
#define ROS_DEBUG_STREAM_NAMED(name, args)
virtual bool getActuatorStateData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_state_data)=0
RequisiteProviderClassLoaderPtr req_provider_loader_
std::shared_ptr< TransmissionClassLoader > TransmissionClassLoaderPtr
TransmissionLoaderData loader_data_
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
std::string demangledTypeName()
pluginlib::ClassLoader< RequisiteProvider > RequisiteProviderClassLoader
virtual ~RequisiteProvider()=default
hardware_interface::VelocityJointInterface velocity_joint_interface
hardware_interface::RobotHW * robot_hw_ptr_
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
std::map< std::string, RawJointData > RawJointDataMap
virtual bool getJointStateData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_state_data)=0
JointToActuatorStateInterface jnt_to_act_state
Parses <transmission> elements into corresponding structs from XML (URDF).
pluginlib::ClassLoader< TransmissionLoader > TransmissionClassLoader
RobotTransmissions * robot_transmissions_ptr_
#define ROS_ERROR_STREAM_NAMED(name, args)
Robot transmissions interface.
bool loadTransmissionMaps(const TransmissionInfo &transmission_info, TransmissionLoaderData &loader_data, TransmissionSharedPtr transmission)
bool load(const std::string &urdf)
Load all transmissions in a URDF.
ActuatorToJointPositionInterface act_to_jnt_pos_cmd
RawJointDataMap raw_joint_data_map
InverseTransmissionInterfaces inverse_transmission_interfaces
bool getActuatorHandles(const std::vector< ActuatorInfo > &actuators_info, hardware_interface::RobotHW *robot_hw, std::vector< Handle > &handles)
hardware_interface::JointStateInterface joint_state_interface
std::shared_ptr< RequisiteProviderClassLoader > RequisiteProviderClassLoaderPtr
TransmissionLoaderData * getData()
TransmissionClassLoaderPtr transmission_class_loader_
JointInterfaces joint_interfaces
JointToActuatorPositionInterface jnt_to_act_pos_cmd
virtual bool getJointCommandData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_cmd_data)=0
JointToActuatorEffortInterface jnt_to_act_eff_cmd
ActuatorData act_state_data
TransmissionSharedPtr transmission
hardware_interface::EffortJointInterface effort_joint_interface
hardware_interface::PositionJointInterface position_joint_interface
ActuatorData act_cmd_data
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
Raw data for a set of joints.
std::shared_ptr< RequisiteProvider > RequisiteProviderPtr
JointToActuatorVelocityInterface jnt_to_act_vel_cmd
Structs to hold transmission data loaded straight from XML (URDF).
ForwardTransmissionInterfaces transmission_interfaces
hardware_interface::RobotHW * robot_hw
Lifecycle is externally controlled (ie. hardware abstraction)
std::vector< TransmissionSharedPtr > transmission_data
static bool hasResource(const std::string &name, const Interface &iface)
Class for loading transmissions from a URDF description into ros_control interfaces.
Contains semantic info about a given transmission loaded from XML (URDF)
TransmissionInterfaceLoader(hardware_interface::RobotHW *robot_hw, RobotTransmissions *robot_transmissions)
virtual bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data)=0
virtual bool getActuatorCommandData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_cmd_data)=0