hardware_interface.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by qiayuan on 12/21/20.
36 //
37 
38 #pragma once
39 
40 #include <vector>
41 #include <string>
42 #include <memory>
43 #include <unordered_map>
44 
45 // ROS
46 #include <ros/ros.h>
47 #include <urdf/model.h>
48 #include <XmlRpcValue.h>
49 
50 // ROS control
56 
62 #include <rm_msgs/ActuatorState.h>
63 #include <rm_msgs/EnableImuTrigger.h>
64 
65 #include "can_bus.h"
66 #include "gpio_manager.h"
67 
68 namespace rm_hw
69 {
70 class RmRobotHW : public hardware_interface::RobotHW
71 {
72 public:
73  RmRobotHW() = default;
83  bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
93  void read(const ros::Time& time, const ros::Duration& period) override;
94 
103  void write(const ros::Time& time, const ros::Duration& period) override;
104 
105  void setCanBusThreadPriority(int thread_priority);
106 
107 private:
115  bool parseActCoeffs(XmlRpc::XmlRpcValue& act_coeffs);
124  bool parseActData(XmlRpc::XmlRpcValue& act_datas, ros::NodeHandle& robot_hw_nh);
133  bool parseImuData(XmlRpc::XmlRpcValue& imu_datas, ros::NodeHandle& robot_hw_nh);
142  bool parseGpioData(XmlRpc::XmlRpcValue& gpio_datas, ros::NodeHandle& robot_hw_nh);
150  bool loadUrdf(ros::NodeHandle& root_nh);
151 
152  bool parseTofData(XmlRpc::XmlRpcValue& tof_datas, ros::NodeHandle& robot_hw_nh);
160  bool setupTransmission(ros::NodeHandle& root_nh);
168  bool setupJointLimit(ros::NodeHandle& root_nh);
175  void publishActuatorState(const ros::Time& time);
176 
177  bool enableImuTrigger(rm_msgs::EnableImuTrigger::Request& req, rm_msgs::EnableImuTrigger::Response& res);
178 
180 
181  bool is_actuator_specified_ = false;
182  int thread_priority_;
183  // Interface
184  std::vector<CanBus*> can_buses_{};
185  GpioManager gpio_manager_{};
194  std::unique_ptr<transmission_interface::TransmissionInterfaceLoader> transmission_loader_{};
200  std::vector<hardware_interface::JointHandle> effort_joint_handles_{};
202 
203  // URDF model of the robot
204  std::string urdf_string_; // for transmission
205  std::shared_ptr<urdf::Model> urdf_model_; // for limit
206 
207  // Actuator
208  std::unordered_map<std::string, ActCoeff> type2act_coeffs_{};
209  std::unordered_map<std::string, std::unordered_map<int, ActData>> bus_id2act_data_{};
210 
211  // Imu
212  std::unordered_map<std::string, std::unordered_map<int, ImuData>> bus_id2imu_data_{};
213 
214  // TF radar
215  std::unordered_map<std::string, std::unordered_map<int, TofData>> bus_id2tof_data_{};
216 
218  std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::ActuatorState>> actuator_state_pub_;
219 };
220 
221 } // namespace rm_hw
rm_hw::RmRobotHW::jnt_to_act_effort_
transmission_interface::JointToActuatorEffortInterface * jnt_to_act_effort_
Definition: hardware_interface.h:259
rm_hw::RmRobotHW::effort_jnt_saturation_interface_
joint_limits_interface::EffortJointSaturationInterface effort_jnt_saturation_interface_
Definition: hardware_interface.h:260
rm_hw::RmRobotHW::actuator_state_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::ActuatorState > > actuator_state_pub_
Definition: hardware_interface.h:280
rm_hw::RmRobotHW::publishActuatorState
void publishActuatorState(const ros::Time &time)
Publish actuator's state to a topic named "/actuator_states".
Definition: hardware_interface.cpp:216
rm_hw::RmRobotHW::bus_id2tof_data_
std::unordered_map< std::string, std::unordered_map< int, TofData > > bus_id2tof_data_
Definition: hardware_interface.h:277
rm_hw::RmRobotHW::act_extra_interface_
rm_control::ActuatorExtraInterface act_extra_interface_
Definition: hardware_interface.h:251
rm_hw::RmRobotHW::bus_id2imu_data_
std::unordered_map< std::string, std::unordered_map< int, ImuData > > bus_id2imu_data_
Definition: hardware_interface.h:274
rm_hw::RmRobotHW::parseActData
bool parseActData(XmlRpc::XmlRpcValue &act_datas, ros::NodeHandle &robot_hw_nh)
Check whether actuator is specified and load specified params.
Definition: parse.cpp:159
gpio_manager.h
rm_hw::RmRobotHW::gpio_state_interface_
rm_control::GpioStateInterface gpio_state_interface_
Definition: hardware_interface.h:248
rm_hw::RmRobotHW::can_buses_
std::vector< CanBus * > can_buses_
Definition: hardware_interface.h:246
rm_hw::RmRobotHW::act_to_jnt_state_
transmission_interface::ActuatorToJointStateInterface * act_to_jnt_state_
Definition: hardware_interface.h:258
ros.h
joint_limits_interface.h
rm_hw::RmRobotHW::robot_state_interface_
rm_control::RobotStateInterface robot_state_interface_
Definition: hardware_interface.h:253
rm_hw::RmRobotHW::parseImuData
bool parseImuData(XmlRpc::XmlRpcValue &imu_datas, ros::NodeHandle &robot_hw_nh)
Check whether some params that are related to imu are set up and load these params.
Definition: parse.cpp:269
rm_hw::RmRobotHW::loadUrdf
bool loadUrdf(ros::NodeHandle &root_nh)
Load urdf of robot from param server.
Definition: parse.cpp:525
rm_control::RobotStateInterface
rm_hw::RmRobotHW::parseGpioData
bool parseGpioData(XmlRpc::XmlRpcValue &gpio_datas, ros::NodeHandle &robot_hw_nh)
Check whether somme params that are related to gpio are set up and load these params.
Definition: parse.cpp:431
can_bus.h
rm_hw::RmRobotHW::setupTransmission
bool setupTransmission(ros::NodeHandle &root_nh)
Set up transmission.
Definition: parse.cpp:534
rm_imu_sensor_interface.h
rm_hw::RmRobotHW::effort_jnt_soft_limits_interface_
joint_limits_interface::EffortJointSoftLimitsInterface effort_jnt_soft_limits_interface_
Definition: hardware_interface.h:261
rm_hw::RmRobotHW::type2act_coeffs_
std::unordered_map< std::string, ActCoeff > type2act_coeffs_
Definition: hardware_interface.h:270
rm_control::GpioStateInterface
transmission_interface::ActuatorToJointStateInterface
ros::ServiceServer
rm_hw::RmRobotHW::urdf_model_
std::shared_ptr< urdf::Model > urdf_model_
Definition: hardware_interface.h:267
actuator_extra_interface.h
joint_limits_interface::EffortJointSoftLimitsInterface
rm_hw::RmRobotHW::gpio_command_interface_
rm_control::GpioCommandInterface gpio_command_interface_
Definition: hardware_interface.h:249
rm_control::GpioCommandInterface
rm_hw::RmRobotHW::imu_sensor_interface_
hardware_interface::ImuSensorInterface imu_sensor_interface_
Definition: hardware_interface.h:254
joint_command_interface.h
hardware_interface::RobotHW
hardware_interface::ActuatorStateInterface
rm_hw::RmRobotHW::service_server_
ros::ServiceServer service_server_
Definition: hardware_interface.h:241
transmission_interface::RobotTransmissions
rm_hw::RmRobotHW::parseTofData
bool parseTofData(XmlRpc::XmlRpcValue &tof_datas, ros::NodeHandle &robot_hw_nh)
Definition: parse.cpp:476
rm_hw::RmRobotHW::enableImuTrigger
bool enableImuTrigger(rm_msgs::EnableImuTrigger::Request &req, rm_msgs::EnableImuTrigger::Response &res)
Definition: hardware_interface.cpp:256
rm_hw::RmRobotHW::setCanBusThreadPriority
void setCanBusThreadPriority(int thread_priority)
Definition: hardware_interface.cpp:211
model.h
rm_hw::RmRobotHW::bus_id2act_data_
std::unordered_map< std::string, std::unordered_map< int, ActData > > bus_id2act_data_
Definition: hardware_interface.h:271
rm_hw::RmRobotHW::thread_priority_
int thread_priority_
Definition: hardware_interface.h:244
rm_hw::RmRobotHW::effort_joint_handles_
std::vector< hardware_interface::JointHandle > effort_joint_handles_
Definition: hardware_interface.h:262
rm_hw::RmRobotHW::gpio_manager_
GpioManager gpio_manager_
Definition: hardware_interface.h:247
rm_control::RmImuSensorInterface
hardware_interface::ImuSensorInterface
rm_hw::RmRobotHW::urdf_string_
std::string urdf_string_
Definition: hardware_interface.h:266
XmlRpcValue.h
rm_hw::RmRobotHW::robot_transmissions_
transmission_interface::RobotTransmissions robot_transmissions_
Definition: hardware_interface.h:257
tof_radar_interface.h
rm_hw::RmRobotHW::read
void read(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Get datas, status of robot.
Definition: hardware_interface.cpp:152
rm_control::ActuatorExtraInterface
rm_hw::RmRobotHW::tof_radar_interface_
rm_control::TofRadarInterface tof_radar_interface_
Definition: hardware_interface.h:263
rm_hw::RmRobotHW::rm_imu_sensor_interface_
rm_control::RmImuSensorInterface rm_imu_sensor_interface_
Definition: hardware_interface.h:255
transmission_interface_loader.h
robot_state_interface.h
joint_state_interface.h
ros::Time
hardware_interface::EffortActuatorInterface
rm_control::TofRadarInterface
rm_hw::RmRobotHW::act_state_interface_
hardware_interface::ActuatorStateInterface act_state_interface_
Definition: hardware_interface.h:250
rm_hw::RmRobotHW::is_actuator_specified_
bool is_actuator_specified_
Definition: hardware_interface.h:243
rm_hw::RmRobotHW::last_publish_time_
ros::Time last_publish_time_
Definition: hardware_interface.h:279
robot_hw.h
rm_hw::RmRobotHW::transmission_loader_
std::unique_ptr< transmission_interface::TransmissionInterfaceLoader > transmission_loader_
Definition: hardware_interface.h:256
rm_hw::RmRobotHW::setupJointLimit
bool setupJointLimit(ros::NodeHandle &root_nh)
Set up joint limit.
Definition: parse.cpp:575
transmission_interface::JointToActuatorEffortInterface
rm_hw
Definition: control_loop.h:48
rm_hw::RmRobotHW::parseActCoeffs
bool parseActCoeffs(XmlRpc::XmlRpcValue &act_coeffs)
Check whether some coefficients that are related to actuator are set up and load these coefficients.
Definition: parse.cpp:81
ros::Duration
rm_hw::RmRobotHW::RmRobotHW
RmRobotHW()=default
rm_hw::RmRobotHW::effort_act_interface_
hardware_interface::EffortActuatorInterface effort_act_interface_
Definition: hardware_interface.h:252
rm_hw::RmRobotHW::write
void write(const ros::Time &time, const ros::Duration &period) override
Comunicate with hardware. Publish command to robot.
Definition: hardware_interface.cpp:183
XmlRpc::XmlRpcValue
rm_hw::RmRobotHW::init
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
Get necessary params from param server. Init hardware_interface.
Definition: hardware_interface.cpp:75
ros::NodeHandle
joint_limits_interface::EffortJointSaturationInterface
gpio_interface.h


rm_hw
Author(s): Qiayuan Liao
autogenerated on Tue May 6 2025 02:23:44