44 handle_data.
name = transmission_info.
name_;
51 if (!act_state_data_ok) {
return false;}
56 if (!act_cmd_data_ok) {
return false;}
66 if (!jnt_data_ok) {
return false;}
72 if (!jnt_state_data_ok) {
return false;}
77 if (!jnt_cmd_data_ok) {
return false;}
90 : robot_hw_ptr_(robot_hw),
91 robot_transmissions_ptr_(robot_transmissions)
95 "transmission_interface::TransmissionLoader"));
99 "transmission_interface::RequisiteProvider"));
102 if (!robot_hw) {
throw std::invalid_argument(
"Invalid robot hardware pointer.");}
103 if (!robot_transmissions) {
throw std::invalid_argument(
"Invalid robot transmissions pointer.");}
112 std::vector<TransmissionInfo> infos;
113 if (!parser.
parse(urdf, infos)) {
return false;}
128 if (!
load(info)) {
return false;}
140 transmission = transmission_loader->load(transmission_info);
141 if (!transmission) {
return false;}
146 "'. Unsupported type '" << transmission_info.
type_ <<
"'.\n" << ex.what());
151 assert(!transmission_info.
joints_.empty() && !transmission_info.
joints_.front().hardware_interfaces_.empty());
152 const std::vector<std::string>& hw_ifaces_ref = transmission_info.
joints_.front().hardware_interfaces_;
161 "Failed to load transmission '" << transmission_info.
name_ <<
162 "'. It has joints with different hardware interfaces. This is currently unsupported.");
168 bool has_at_least_one_hw_iface =
false;
169 BOOST_FOREACH(
const std::string& hw_iface, hw_ifaces_ref)
175 if (!req_provider) {
continue;}
180 "' hardware interface for transmission '" << transmission_info.
name_ <<
181 "'.\n" << ex.what());
185 const bool load_ok = req_provider->loadTransmissionMaps(transmission_info,
loader_data_, transmission);
186 if (load_ok) {has_at_least_one_hw_iface =
true;}
190 if (!has_at_least_one_hw_iface)
193 "'. It contains no valid hardware interfaces.");
RobotTransmissions * robot_transmissions_ptr_
ActuatorData act_cmd_data
TransmissionSharedPtr transmission
RequisiteProviderClassLoaderPtr req_provider_loader_
static bool parse(const std::string &urdf_string, std::vector< TransmissionInfo > &transmissions)
Parses the tranmission elements of a URDF.
JointInterfaces joint_interfaces
hardware_interface::RobotHW * robot_hw
Lifecycle is externally controlled (ie. hardware abstraction)
Parse all transmissions specified in a URDF.
#define ROS_ERROR_STREAM_NAMED(name, args)
hardware_interface::RobotHW * robot_hw_ptr_
TransmissionInterfaceLoader(hardware_interface::RobotHW *robot_hw, RobotTransmissions *robot_transmissions)
TransmissionClassLoaderPtr transmission_class_loader_
Contains semantic info about a given joint loaded from XML (URDF)
Contains semantic info about a given transmission loaded from XML (URDF)
Robot transmissions interface.
bool load(const std::string &urdf)
Load all transmissions in a URDF.
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.
virtual bool getActuatorCommandData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_cmd_data)=0
bool is_permutation(ForwardIt1 first, ForwardIt1 last, ForwardIt2 d_first)
virtual bool getActuatorStateData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_state_data)=0
RawJointDataMap raw_joint_data_map
pluginlib::ClassLoader< TransmissionLoader > TransmissionClassLoader
pluginlib::ClassLoader< RequisiteProvider > RequisiteProviderClassLoader
virtual bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data)=0
TransmissionLoaderData loader_data_
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
virtual bool getJointStateData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_state_data)=0
bool loadTransmissionMaps(const TransmissionInfo &transmission_info, TransmissionLoaderData &loader_data, TransmissionSharedPtr transmission)
std::vector< TransmissionSharedPtr > transmission_data
std::vector< JointInfo > joints_
std::vector< std::string > hardware_interfaces_
virtual bool getJointCommandData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_cmd_data)=0
#define ROS_WARN_STREAM_NAMED(name, args)
ActuatorData act_state_data