joint_state_interface_provider.cpp
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 
29 // Pluginlib
31 
32 // ros_control
34 
35 namespace transmission_interface
36 {
37 
40  JointInterfaces& joint_interfaces,
41  RawJointDataMap& raw_joint_data_map)
42 {
43  // If interface does not yet exist in robot hardware abstraction, add it and use internal data structures
45  if (!robot_hw->get<JointStateInterface>())
46  {
47  robot_hw->registerInterface(&joint_interfaces.joint_state_interface);
48  }
49  JointStateInterface& interface = *(robot_hw->get<JointStateInterface>());
50 
51  // Register joints on the hardware interface
52  BOOST_FOREACH(const JointInfo& joint_info, transmission_info.joints_)
53  {
54  const std::string& name = joint_info.name_;
55 
56  // Do nothing if joint already exists on the hardware interface
57  if (hasResource(name, interface)) {continue;}
58 
59  // Update hardware interface
61  RawJointData& raw_joint_data = raw_joint_data_map[name]; // Add joint if it does not yet exist
62  JointStateHandle handle(name,
63  &raw_joint_data.position,
64  &raw_joint_data.velocity,
65  &raw_joint_data.effort);
66  interface.registerHandle(handle);
67  }
68  return true;
69 }
70 
72  const RawJointDataMap& raw_joint_data_map,
73  JointData& jnt_state_data)
74 {
75  const unsigned int dim = transmission_info.joints_.size();
76  jnt_state_data.position.resize(dim);
77  jnt_state_data.velocity.resize(dim);
78  jnt_state_data.effort.resize(dim);
79 
80  for (unsigned int i = 0; i < dim; ++i)
81  {
82  const std::string& joint_name = transmission_info.joints_[i].name_;
83  RawJointDataMap::const_iterator raw_joint_data_it = raw_joint_data_map.find(joint_name);
84  if (raw_joint_data_it == raw_joint_data_map.end()) {return false;} // Joint name not found!
85  const RawJointData& raw_joint_data = raw_joint_data_it->second;
86 
87  // TODO: Get rid of these const casts!
88  jnt_state_data.position[i] = const_cast<double*>(&(raw_joint_data.position));
89  jnt_state_data.velocity[i] = const_cast<double*>(&(raw_joint_data.velocity));
90  jnt_state_data.effort[i] = const_cast<double*>(&(raw_joint_data.effort));
91  }
92 
93  return true;
94 }
95 
98  ActuatorData& act_state_data)
99 {
102 
103  // Get handles to all required actuators
104  std::vector<ActuatorStateHandle> handles;
105  if (!this->getActuatorHandles<ActuatorStateInterface, ActuatorStateHandle>(transmission_info.actuators_,
106  robot_hw,
107  handles)) {return false;}
108 
109  // Populate actuator data
110  const unsigned int dim = transmission_info.actuators_.size();
111  act_state_data.position.resize(dim);
112  act_state_data.velocity.resize(dim);
113  act_state_data.effort.resize(dim);
114 
115  for (unsigned int i = 0; i < dim; ++i)
116  {
117  // TODO: Get rid of these const casts!
118  act_state_data.position[i] = const_cast<double*>(handles[i].getPositionPtr());
119  act_state_data.velocity[i] = const_cast<double*>(handles[i].getVelocityPtr());
120  act_state_data.effort[i] = const_cast<double*>(handles[i].getEffortPtr());
121  }
122  return true;
123 }
124 
126  TransmissionHandleData& handle_data)
127 {
128  // If interface does not yet exist in the robot transmissions, add it and use internal data structures
130  {
132  }
134 
135  // Update transmission interface
136  ActuatorToJointStateHandle handle(handle_data.name,
137  handle_data.transmission.get(),
138  handle_data.act_state_data,
139  handle_data.jnt_state_data);
140  interface.registerHandle(handle);
141  return true;
142 }
143 
144 } // namespace
145 
bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data)
std::vector< double * > velocity
Definition: transmission.h:64
bool getJointStateData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_state_data)
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:61
std::vector< double * > position
Definition: transmission.h:52
Contains semantic info about a given joint loaded from XML (URDF)
Contains semantic info about a given transmission loaded from XML (URDF)
bool updateJointInterfaces(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map)
Update a robot&#39;s joint interfaces with joint information contained in a transmission.
Joint interfaces of a robot. Only used interfaces need to be populated.
Handle for propagating actuator state (position, velocity and effort) to joint state for a given tran...
static bool hasResource(const std::string &name, const Interface &iface)
hardware_interface::JointStateInterface joint_state_interface
bool getActuatorStateData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_state_data)
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:50
std::vector< double * > velocity
Definition: transmission.h:53
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
std::vector< double * > position
Definition: transmission.h:63
std::vector< double * > effort
Definition: transmission.h:65
std::vector< ActuatorInfo > actuators_
PLUGINLIB_EXPORT_CLASS(transmission_interface::BiDirectionalEffortJointInterfaceProvider, transmission_interface::RequisiteProvider)
std::vector< double * > effort
Definition: transmission.h:54
std::map< std::string, RawJointData > RawJointDataMap


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:17