30 #ifndef TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_LOADER_H 31 #define TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_LOADER_H 42 #include <boost/foreach.hpp> 43 #include <boost/shared_ptr.hpp> 73 template<
class ForwardIt1,
class ForwardIt2>
78 std::pair<ForwardIt1, ForwardIt2> pair = std::mismatch(first, last, d_first);
79 first = pair.first; d_first = pair.second;
84 ForwardIt2 d_last = d_first;
85 std::advance(d_last, std::distance(first, last));
86 for (ForwardIt1 i = first; i != last; ++i) {
87 if (i != std::find(first, i, *i))
continue;
89 int m = std::count(d_first, d_last, *i);
90 if (m==0 || std::count(i, last, *i) != m) {
111 : position(
std::numeric_limits<double>::quiet_NaN()),
112 velocity(
std::numeric_limits<double>::quiet_NaN()),
113 effort(
std::numeric_limits<double>::quiet_NaN()),
114 position_cmd(
std::numeric_limits<double>::quiet_NaN()),
115 velocity_cmd(
std::numeric_limits<double>::quiet_NaN()),
116 effort_cmd(
std::numeric_limits<double>::quiet_NaN())
162 robot_transmissions(0)
194 virtual bool updateJointInterfaces(
const TransmissionInfo& transmission_info,
197 RawJointDataMap& raw_joint_data_map) = 0;
214 const RawJointDataMap& raw_joint_data_map,
218 const RawJointDataMap& raw_joint_data_map,
221 virtual bool getActuatorStateData(
const TransmissionInfo& transmission_info,
225 virtual bool getActuatorCommandData(
const TransmissionInfo& transmission_info,
232 template <
class Interface>
233 static bool hasResource(
const std::string& name,
const Interface& iface)
238 const std::vector<std::string>& existing_resources = iface.getNames();
239 if (existing_resources.end() != std::find(existing_resources.begin(), existing_resources.end(), name))
242 demangledTypeName<Interface>());
248 demangledTypeName<Interface>());
253 template <
class HardwareInterface,
class Handle>
256 std::vector<Handle>& handles)
262 HardwareInterface* hw_iface = robot_hw->
get<HardwareInterface>();
268 demangledTypeName<HardwareInterface>() <<
"'.");
277 handles.push_back(hw_iface->getHandle(info.
name_));
279 catch(
const HardwareInterfaceException& ex)
282 "' does not expose the required hardware interface '" <<
283 demangledTypeName<HardwareInterface>() <<
"'.");
382 bool load(
const std::string& urdf);
392 bool load(
const std::vector<TransmissionInfo>& transmission_info_vec);
426 #endif // header guard bool getActuatorHandles(const std::vector< ActuatorInfo > &actuators_info, hardware_interface::RobotHW *robot_hw, std::vector< Handle > &handles)
RobotTransmissions * robot_transmissions_ptr_
ActuatorData act_cmd_data
TransmissionSharedPtr transmission
RequisiteProviderClassLoaderPtr req_provider_loader_
JointInterfaces joint_interfaces
hardware_interface::RobotHW * robot_hw
Lifecycle is externally controlled (ie. hardware abstraction)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
hardware_interface::RobotHW * robot_hw_ptr_
TransmissionClassLoaderPtr transmission_class_loader_
ActuatorToJointPositionInterface act_to_jnt_pos_cmd
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
Contains semantic info about a given actuator loaded from XML (URDF)
Parses <transmission> elements into corresponding structs from XML (URDF).
ActuatorToJointEffortInterface act_to_jnt_eff_cmd
Contains semantic info about a given transmission loaded from XML (URDF)
hardware_interface::VelocityJointInterface velocity_joint_interface
Robot transmissions interface.
boost::shared_ptr< Transmission > TransmissionPtr
JointToActuatorEffortInterface jnt_to_act_eff_cmd
std::string demangledTypeName()
JointToActuatorPositionInterface jnt_to_act_pos_cmd
InverseTransmissionInterfaces inverse_transmission_interfaces
Class for loading transmissions from a URDF description into ros_control interfaces.
hardware_interface::EffortJointInterface effort_joint_interface
Joint interfaces of a robot. Only used interfaces need to be populated.
Structs to hold tranmission data loaded straight from XML (URDF).
bool is_permutation(ForwardIt1 first, ForwardIt1 last, ForwardIt2 d_first)
ForwardTransmissionInterfaces transmission_interfaces
static bool hasResource(const std::string &name, const Interface &iface)
hardware_interface::JointStateInterface joint_state_interface
RawJointDataMap raw_joint_data_map
pluginlib::ClassLoader< TransmissionLoader > TransmissionClassLoader
boost::shared_ptr< RequisiteProvider > RequisiteProviderPtr
pluginlib::ClassLoader< RequisiteProvider > RequisiteProviderClassLoader
ActuatorToJointVelocityInterface act_to_jnt_vel_cmd
boost::shared_ptr< RequisiteProviderClassLoader > RequisiteProviderClassLoaderPtr
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
boost::shared_ptr< TransmissionClassLoader > TransmissionClassLoaderPtr
JointToActuatorStateInterface jnt_to_act_state
TransmissionLoaderData loader_data_
ActuatorToJointStateInterface act_to_jnt_state
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
virtual ~RequisiteProvider()
JointToActuatorVelocityInterface jnt_to_act_vel_cmd
std::vector< TransmissionSharedPtr > transmission_data
hardware_interface::PositionJointInterface position_joint_interface
std::map< std::string, RawJointData > RawJointDataMap
TransmissionLoaderData * getData()
Raw data for a set of joints.
ActuatorData act_state_data