Go to the documentation of this file.
47 raw_joint_data_map)) {
return false;}
51 if (!robot_hw->
get<EffortJointInterface>())
55 EffortJointInterface&
interface = *(robot_hw->
get<EffortJointInterface>());
58 for (
const auto& joint_info : transmission_info.
joints_)
60 const std::string& name = joint_info.name_;
70 interface.registerHandle(handle);
79 const unsigned int dim = transmission_info.
joints_.size();
80 jnt_cmd_data.
effort.resize(dim);
82 for (
unsigned int i = 0; i < dim; ++i)
84 const std::string& joint_name = transmission_info.
joints_[i].name_;
85 RawJointDataMap::const_iterator raw_joint_data_it = raw_joint_data_map.find(joint_name);
86 if (raw_joint_data_it == raw_joint_data_map.end()) {
return false;}
87 const RawJointData& raw_joint_data = raw_joint_data_it->second;
104 std::vector<ActuatorHandle> handles;
105 if (!this->getActuatorHandles<EffortActuatorInterface, ActuatorHandle>(transmission_info.
actuators_,
107 handles)) {
return false;}
110 const unsigned int dim = transmission_info.
actuators_.size();
111 act_cmd_data.
effort.resize(dim);
113 for (
unsigned int i = 0; i < dim; ++i)
116 act_cmd_data.
effort[i] =
const_cast<double*
>(handles[i].getCommandPtr());
142 interface.registerHandle(handle);
Handle for propagating joint efforts to actuator efforts for a given transmission.
Joint interfaces of a robot. Only used interfaces need to be populated.
ActuatorToJointStateInterface act_to_jnt_state
JointStateHandle getHandle(const std::string &name)
void registerInterface(T *iface)
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data) override
std::vector< JointInfo > joints_
std::vector< ActuatorInfo > actuators_
bool updateJointInterfaces(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map) override
Update a robot's joint interfaces with joint information contained in a transmission.
bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data) override
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
std::map< std::string, RawJointData > RawJointDataMap
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool updateJointInterfaces(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map) override
Update a robot's joint interfaces with joint information contained in a transmission.
std::vector< double * > effort
bool getJointCommandData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_cmd_data) override
hardware_interface::JointStateInterface joint_state_interface
std::vector< double * > effort
JointToActuatorEffortInterface jnt_to_act_eff_cmd
TransmissionSharedPtr transmission
bool getActuatorCommandData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_cmd_data) override
hardware_interface::EffortJointInterface effort_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.
ForwardTransmissionInterfaces transmission_interfaces
static bool hasResource(const std::string &name, const Interface &iface)
Contains semantic info about a given transmission loaded from XML (URDF)