dynamixel_interface_controller.h
Go to the documentation of this file.
1 /* CSIRO Open Source Software License Agreement (variation of the BSD / MIT License)
2  * Copyright (c) 2020, Commonwealth Scientific and Industrial Research Organisation (CSIRO) ABN 41 687 119 230.
3  * All rights reserved. CSIRO is willing to grant you a license to the dynamixel_actuator ROS packages on the following
4  * terms, except where otherwise indicated for third party material. Redistribution and use of this software in source
5  * and binary forms, with or without modification, are permitted provided that the following conditions are met:
6  * - Redistributions of source code must retain the above copyright notice, this list of conditions and the following
7  * disclaimer.
8  * - Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following
9  * disclaimer in the documentation and/or other materials provided with the distribution.
10  * - Neither the name of CSIRO nor the names of its contributors may be used to endorse or promote products derived from
11  * this software without specific prior written permission of CSIRO.
12  *
13  * EXCEPT AS EXPRESSLY STATED IN THIS AGREEMENT AND TO THE FULL EXTENT PERMITTED BY APPLICABLE LAW, THE SOFTWARE IS
14  * PROVIDED "AS-IS". CSIRO MAKES NO REPRESENTATIONS, WARRANTIES OR CONDITIONS OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
15  * BUT NOT LIMITED TO ANY REPRESENTATIONS, WARRANTIES OR CONDITIONS REGARDING THE CONTENTS OR ACCURACY OF THE SOFTWARE,
16  * OR OF TITLE, MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, NON-INFRINGEMENT, THE ABSENCE OF LATENT OR OTHER
17  * DEFECTS, OR THE PRESENCE OR ABSENCE OF ERRORS, WHETHER OR NOT DISCOVERABLE.
18  * TO THE FULL EXTENT PERMITTED BY APPLICABLE LAW, IN NO EVENT SHALL CSIRO BE LIABLE ON ANY LEGAL THEORY (INCLUDING,
19  * WITHOUT LIMITATION, IN AN ACTION FOR BREACH OF CONTRACT, NEGLIGENCE OR OTHERWISE) FOR ANY CLAIM, LOSS, DAMAGES OR
20  * OTHER LIABILITY HOWSOEVER INCURRED. WITHOUT LIMITING THE SCOPE OF THE PREVIOUS SENTENCE THE EXCLUSION OF LIABILITY
21  * SHALL INCLUDE: LOSS OF PRODUCTION OR OPERATION TIME, LOSS, DAMAGE OR CORRUPTION OF DATA OR RECORDS; OR LOSS OF
22  * ANTICIPATED SAVINGS, OPPORTUNITY, REVENUE, PROFIT OR GOODWILL, OR OTHER ECONOMIC LOSS; OR ANY SPECIAL, INCIDENTAL,
23  * INDIRECT, CONSEQUENTIAL, PUNITIVE OR EXEMPLARY DAMAGES, ARISING OUT OF OR IN CONNECTION WITH THIS AGREEMENT, ACCESS
24  * OF THE SOFTWARE OR ANY OTHER DEALINGS WITH THE SOFTWARE, EVEN IF CSIRO HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH
25  * CLAIM, LOSS, DAMAGES OR OTHER LIABILITY. APPLICABLE LEGISLATION SUCH AS THE AUSTRALIAN CONSUMER LAW MAY APPLY
26  * REPRESENTATIONS, WARRANTIES, OR CONDITIONS, OR IMPOSES OBLIGATIONS OR LIABILITY ON CSIRO THAT CANNOT BE EXCLUDED,
27  * RESTRICTED OR MODIFIED TO THE FULL EXTENT SET OUT IN THE EXPRESS TERMS OF THIS CLAUSE ABOVE "CONSUMER GUARANTEES".
28  * TO THE EXTENT THAT SUCH CONSUMER GUARANTEES CONTINUE TO APPLY, THEN TO THE FULL EXTENT PERMITTED BY THE APPLICABLE
29  * LEGISLATION, THE LIABILITY OF CSIRO UNDER THE RELEVANT CONSUMER GUARANTEE IS LIMITED (WHERE PERMITTED AT CSIRO'S
30  * OPTION) TO ONE OF FOLLOWING REMEDIES OR SUBSTANTIALLY EQUIVALENT REMEDIES:
31  * (a) THE REPLACEMENT OF THE SOFTWARE, THE SUPPLY OF EQUIVALENT SOFTWARE, OR SUPPLYING RELEVANT SERVICES AGAIN;
32  * (b) THE REPAIR OF THE SOFTWARE;
33  * (c) THE PAYMENT OF THE COST OF REPLACING THE SOFTWARE, OF ACQUIRING EQUIVALENT SOFTWARE, HAVING THE RELEVANT
34  * SERVICES SUPPLIED AGAIN, OR HAVING THE SOFTWARE REPAIRED.
35  * IN THIS CLAUSE, CSIRO INCLUDES ANY THIRD PARTY AUTHOR OR OWNER OF ANY PART OF THE SOFTWARE OR MATERIAL DISTRIBUTED
36  * WITH IT. CSIRO MAY ENFORCE ANY RIGHTS ON BEHALF OF THE RELEVANT THIRD PARTY.
37  *
38  * Third Party Components:
39  *
40  * The following third party components are distributed with the Software. You agree to comply with the license terms
41  * for these components as part of accessing the Software. Other third party software may also be identified in
42  * separate files distributed with the Software.
43  * ___________________________________________________________________
44  *
45  * dynamixel_interface is forked from projects authored by Brian
46  * Axelrod (on behalf of Willow Garage):
47  *
48  * https://github.com/baxelrod/dynamixel_pro_controller
49  * https://github.com/baxelrod/dynamixel_pro_driver
50  *
51  * Thus they retain the following notice:
52  *
53  * Software License Agreement (BSD License)
54  * Copyright (c) 2013, Willow Garage
55  * All rights reserved.
56  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
57  * following conditions are met:
58  * - Redistributions of source code must retain the above copyright notice, this list of conditions and the following
59  * disclaimer.
60  * - Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
61  * following disclaimer in the documentation and/or other materials provided with the distribution.
62  * - Neither the name of Willow Garage nor the names of its contributors may be used to endorse or promote products
63  * derived from this software without specific prior written permission.
64  *
65  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
66  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
67  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
68  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
69  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
70  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
71  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
72  * ___________________________________________________________________
73  */
74 
82 #ifndef DYNAMIXEL_INTERFACE_CONTROLLER_H_
83 #define DYNAMIXEL_INTERFACE_CONTROLLER_H_
84 
85 #include <algorithm>
86 #include <map>
87 #include <memory>
88 #include <mutex>
89 #include <string>
90 
91 #include <XmlRpcValue.h>
92 
93 #include <ros/callback_queue.h>
94 #include <ros/ros.h>
95 #include <ros/spinner.h>
96 #include <sensor_msgs/JointState.h>
97 
99 
100 #include <dynamixel_interface/DataPort.h>
101 #include <dynamixel_interface/DataPorts.h>
102 #include <dynamixel_interface/ServoDiag.h>
103 #include <dynamixel_interface/ServoDiags.h>
104 
105 namespace dynamixel_interface
106 {
109 {
110  int id;
111  std::string joint_name;
112 
113  double max_vel;
114  double torque_limit;
115 
116  int zero_pos;
117  int min_pos;
118  int max_pos;
119 
121 
124  uint8_t hardware_status;
125 };
126 
128 struct PortInfo
129 {
130  std::string port_name;
131 
132  std::string device;
133  int baudrate;
134 
136 
137  std::unique_ptr<DynamixelInterfaceDriver> driver;
138 
139  std::unordered_map<std::string, DynamixelInfo> joints;
140 };
141 
149 {
150 public:
154 
157 
160  bool parseParameters(void);
161 
166  // - check response on bus
170  bool initialise();
171 
174  inline double getLoopRate(void) { return loop_rate_; };
175 
178  void loop(void);
179 
180 private:
185 
191 
195  bool initialisePort(PortInfo &port);
196 
203 
207  void jointStateCallback(const sensor_msgs::JointState::ConstPtr &joint_commands);
208 
215  void multiThreadedIO(PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataport_msg,
216  dynamixel_interface::ServoDiags &status_msg, bool perform_write) const;
217 
221  void multiThreadedWrite(PortInfo &port, sensor_msgs::JointState joint_commands) const;
222 
228  void multiThreadedRead(PortInfo &port, sensor_msgs::JointState &read_msg,
229  dynamixel_interface::DataPorts &dataports_msg,
230  dynamixel_interface::ServoDiags &diags_msg) const;
231 
232  std::unique_ptr<ros::NodeHandle> nh_;
233 
234  std::vector<PortInfo> dynamixel_ports_;
235 
236  sensor_msgs::JointState write_msg_;
237 
238  std::mutex write_mutex_;
239  bool write_ready_ = false;
240 
242 
247 
249 
250  // variables for tracking diagnostics reading rate
254 
255  // variables for tracking dataport reading rate
257  uint dataport_counter_ = 0;
258  uint dataport_iters_ = 0;
259 
261 
262  bool parameters_parsed_ = false;
263  bool initialised_ = false;
264 
267 
270 
271  double loop_rate_;
273  double dataport_rate_;
275 };
276 
277 } // namespace dynamixel_interface
278 
279 #endif // DYNAMIXEL_INTERFACE_CONTROLLER_H_
dynamixel_interface::DynamixelInfo::torque_limit
double torque_limit
Motor maximum torque limit (rated max)
Definition: dynamixel_interface_controller.h:114
dynamixel_interface::DynamixelInterfaceController::recv_queue_size_
int recv_queue_size_
Receive queue size for desired_joint_states topic.
Definition: dynamixel_interface_controller.h:274
dynamixel_interface::DynamixelInfo::model_spec
const DynamixelSpec * model_spec
Motor model specification including encoder counts and unit conversion factors.
Definition: dynamixel_interface_controller.h:120
dynamixel_interface::DynamixelInterfaceController::parseParameters
bool parseParameters(void)
Definition: dynamixel_interface_controller.cpp:131
ros::Publisher
dynamixel_interface::DynamixelInterfaceController::write_ready_
bool write_ready_
Booleans indicating if we have received commands.
Definition: dynamixel_interface_controller.h:239
dynamixel_interface::DynamixelInfo
Struct that describes each servo's place in the system including which joint it corresponds to.
Definition: dynamixel_interface_controller.h:108
spinner.h
dynamixel_interface::DynamixelInterfaceController::dataport_iters_
uint dataport_iters_
publish when dataport_counter_ == this
Definition: dynamixel_interface_controller.h:258
ros.h
dynamixel_interface::DynamixelInterfaceController::write_mutex_
std::mutex write_mutex_
Mutex for write_msg, as there are potentially multiple threads.
Definition: dynamixel_interface_controller.h:238
dynamixel_interface::DynamixelInfo::current_mode
DynamixelControlMode current_mode
control mode (position, velocity, torque)
Definition: dynamixel_interface_controller.h:123
dynamixel_interface::DynamixelInterfaceController::multiThreadedIO
void multiThreadedIO(PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataport_msg, dynamixel_interface::ServoDiags &status_msg, bool perform_write) const
Definition: dynamixel_interface_controller.cpp:1105
dynamixel_interface::DynamixelInterfaceController::parameters_parsed_
bool parameters_parsed_
method of control (position/velocity/torque)
Definition: dynamixel_interface_controller.h:262
dynamixel_interface_driver.h
Defines the hardware abstraction methods for communicating with dynamixels.
dynamixel_interface::DynamixelInterfaceController::diagnostics_rate_
double diagnostics_rate_
Desired rate at which servo diagnostic information is published.
Definition: dynamixel_interface_controller.h:272
dynamixel_interface::DynamixelInterfaceController::parseServoInformation
bool parseServoInformation(PortInfo &port, XmlRpc::XmlRpcValue servos)
Definition: dynamixel_interface_controller.cpp:420
dynamixel_interface::DynamixelInterfaceController::multiThreadedRead
void multiThreadedRead(PortInfo &port, sensor_msgs::JointState &read_msg, dynamixel_interface::DataPorts &dataports_msg, dynamixel_interface::ServoDiags &diags_msg) const
Definition: dynamixel_interface_controller.cpp:1374
dynamixel_interface::DynamixelInterfaceController::diagnostics_counter_
uint diagnostics_counter_
Counter for tracking diagnostics rate.
Definition: dynamixel_interface_controller.h:252
dynamixel
dynamixel_interface::PortInfo
Struct which stores information about each port in use and which joints use that port.
Definition: dynamixel_interface_controller.h:128
dynamixel_interface::DynamixelInterfaceController::initialiseDynamixel
bool initialiseDynamixel(PortInfo &port, DynamixelInfo &dynamixel)
Definition: dynamixel_interface_controller.cpp:711
dynamixel_interface::DynamixelInterfaceController::dataport_counter_
uint dataport_counter_
counter for tracking dataport rate
Definition: dynamixel_interface_controller.h:257
dynamixel_interface::DynamixelInterfaceController::initialise
bool initialise()
Definition: dynamixel_interface_controller.cpp:571
dynamixel_interface::DynamixelSpec
Struct that describes the dynamixel motor's static and physical properties.
Definition: dynamixel_interface_driver.h:99
dynamixel_interface::DynamixelInfo::max_pos
int max_pos
Motor maximum encoder value. Note that if min > max, the motor direction is reversed.
Definition: dynamixel_interface_controller.h:118
dynamixel_interface::DynamixelInterfaceController::joint_state_publisher_
ros::Publisher joint_state_publisher_
Publishes joint states from reads.
Definition: dynamixel_interface_controller.h:243
dynamixel_interface::DynamixelInterfaceController::loop_rate_
double loop_rate_
Desired loop rate (joint states are published at this rate)
Definition: dynamixel_interface_controller.h:271
dynamixel_interface::PortInfo::port_name
std::string port_name
User defined port name.
Definition: dynamixel_interface_controller.h:130
dynamixel_interface::DynamixelInterfaceController::write_msg_
sensor_msgs::JointState write_msg_
Stores the last message received from the write command topic.
Definition: dynamixel_interface_controller.h:236
dynamixel_interface::DynamixelControlMode
DynamixelControlMode
Definition: dynamixel_const.h:368
dynamixel_interface::DynamixelInterfaceController::diagnostics_publisher_
ros::Publisher diagnostics_publisher_
Publishes joint states from reads.
Definition: dynamixel_interface_controller.h:244
dynamixel_interface::DynamixelInterfaceController::control_type_
DynamixelControlMode control_type_
Definition: dynamixel_interface_controller.h:260
XmlRpcValue.h
dynamixel_interface::DynamixelInterfaceController::dynamixel_ports_
std::vector< PortInfo > dynamixel_ports_
method of control (position/velocity/torque)
Definition: dynamixel_interface_controller.h:234
dynamixel_interface::DynamixelInterfaceController::ignore_input_velocity_
bool ignore_input_velocity_
can set driver to ignore profile velocity commands in position mode
Definition: dynamixel_interface_controller.h:266
dynamixel_interface::DynamixelInterfaceController::read_dataport_
bool read_dataport_
Bool for telling threads to read dataport data.
Definition: dynamixel_interface_controller.h:256
callback_queue.h
dynamixel_interface::DynamixelInfo::min_pos
int min_pos
Motor minimum encoder value. Note that if min > max, the motor direction is reversed.
Definition: dynamixel_interface_controller.h:117
dynamixel_interface::DynamixelInterfaceController::~DynamixelInterfaceController
~DynamixelInterfaceController()
Destructor, deletes the objects holding the serial ports and disables the motors if required.
Definition: dynamixel_interface_controller.cpp:111
dynamixel_interface::DynamixelInterfaceController::read_diagnostics_
bool read_diagnostics_
Bool for telling threads to read diagnostics data.
Definition: dynamixel_interface_controller.h:251
dynamixel_interface::DynamixelInterfaceController::debug_publisher_
ros::Publisher debug_publisher_
Debug message publisher.
Definition: dynamixel_interface_controller.h:246
dynamixel_interface::DynamixelInfo::joint_name
std::string joint_name
The unique (globally) name of the joint.
Definition: dynamixel_interface_controller.h:111
dynamixel_interface::DynamixelInterfaceController::multiThreadedWrite
void multiThreadedWrite(PortInfo &port, sensor_msgs::JointState joint_commands) const
Definition: dynamixel_interface_controller.cpp:1123
dynamixel_interface::PortInfo::use_legacy_protocol
bool use_legacy_protocol
boolean indicating if legacy protocol (for older series dynamixels) is in use
Definition: dynamixel_interface_controller.h:135
dynamixel_interface::PortInfo::baudrate
int baudrate
Serial baud rate.
Definition: dynamixel_interface_controller.h:133
dynamixel_interface::DynamixelInterfaceController::broadcast_timer_
ros::Timer broadcast_timer_
Timer that controls the rate of the IO callback.
Definition: dynamixel_interface_controller.h:248
dynamixel_interface::DynamixelInterfaceController::dataport_rate_
double dataport_rate_
Rate at which the pro external dataport is read.
Definition: dynamixel_interface_controller.h:273
dynamixel_interface::DynamixelInterfaceController::global_torque_limit_
double global_torque_limit_
global joint torque limit
Definition: dynamixel_interface_controller.h:269
dynamixel_interface::DynamixelInterfaceController::DynamixelInterfaceController
DynamixelInterfaceController()
Definition: dynamixel_interface_controller.cpp:104
dynamixel_interface::DynamixelInterfaceController::getLoopRate
double getLoopRate(void)
Definition: dynamixel_interface_controller.h:174
dynamixel_interface::DynamixelInterfaceController::initialised_
bool initialised_
Bool indicating if we are ready for operation.
Definition: dynamixel_interface_controller.h:263
dynamixel_interface::PortInfo::driver
std::unique_ptr< DynamixelInterfaceDriver > driver
The driver object.
Definition: dynamixel_interface_controller.h:137
dynamixel_interface::DynamixelInterfaceController::dataport_publisher_
ros::Publisher dataport_publisher_
Publishes the data from the external ports on dynamixel_pros.
Definition: dynamixel_interface_controller.h:245
dynamixel_interface::DynamixelInterfaceController::joint_state_subscriber_
ros::Subscriber joint_state_subscriber_
Gets joint states for writes.
Definition: dynamixel_interface_controller.h:241
dynamixel_interface::DynamixelInterfaceController::jointStateCallback
void jointStateCallback(const sensor_msgs::JointState::ConstPtr &joint_commands)
Definition: dynamixel_interface_controller.cpp:883
dynamixel_interface::DynamixelInfo::max_vel
double max_vel
Motor maximum joint velocity (rad/s)
Definition: dynamixel_interface_controller.h:113
dynamixel_interface::DynamixelInterfaceController::parsePortInformation
bool parsePortInformation(XmlRpc::XmlRpcValue ports)
Definition: dynamixel_interface_controller.cpp:267
dynamixel_interface::DynamixelInterfaceController::stop_motors_on_shutdown_
bool stop_motors_on_shutdown_
Indicates if the motors should be turned off when the controller stops.
Definition: dynamixel_interface_controller.h:265
dynamixel_interface::DynamixelInterfaceController
Definition: dynamixel_interface_controller.h:148
dynamixel_interface::DynamixelInterfaceController::diagnostics_iters_
uint diagnostics_iters_
publish when diagnostic_counter_ == this
Definition: dynamixel_interface_controller.h:253
dynamixel_interface::DynamixelInterfaceController::loop
void loop(void)
Definition: dynamixel_interface_controller.cpp:958
dynamixel_interface::DynamixelInterfaceController::initialisePort
bool initialisePort(PortInfo &port)
Definition: dynamixel_interface_controller.cpp:607
dynamixel_interface::DynamixelInfo::id
int id
The unique (per port) ID of the motor.
Definition: dynamixel_interface_controller.h:110
dynamixel_interface::PortInfo::joints
std::unordered_map< std::string, DynamixelInfo > joints
map of joint information by name
Definition: dynamixel_interface_controller.h:139
dynamixel_interface::DynamixelInfo::torque_enabled
bool torque_enabled
Motor enable flag.
Definition: dynamixel_interface_controller.h:122
dynamixel_interface
Definition: dynamixel_const.h:92
ros::Timer
dynamixel_interface::PortInfo::device
std::string device
Serial device name.
Definition: dynamixel_interface_controller.h:132
dynamixel_interface::DynamixelInterfaceController::global_max_vel_
double global_max_vel_
global joint speed limit
Definition: dynamixel_interface_controller.h:268
dynamixel_interface::DynamixelInfo::zero_pos
int zero_pos
Motor initial position (in raw encoder values). This value defines the 0 radian position.
Definition: dynamixel_interface_controller.h:116
dynamixel_interface::DynamixelInfo::hardware_status
uint8_t hardware_status
current motor status, used for hardware error reporting
Definition: dynamixel_interface_controller.h:124
XmlRpc::XmlRpcValue
ros::Subscriber
dynamixel_interface::DynamixelInterfaceController::nh_
std::unique_ptr< ros::NodeHandle > nh_
Handler for the ROS Node.
Definition: dynamixel_interface_controller.h:232


dynamixel_interface
Author(s): Tom Molnar
autogenerated on Wed Mar 2 2022 00:13:19