rm_control
Loading...
Searching...
No Matches
rm_robot_hw_sim.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 2/10/21.
36//
37
38#pragma once
39
40#include <gazebo_ros_control/default_robot_hw_sim.h>
44#include <std_srvs/Trigger.h>
45
46namespace rm_gazebo
47{
49{
50 hardware_interface::JointHandle joint_;
51 double posDes_{}, velDes_{}, kp_{}, kd_{}, ff_{};
52};
53
55{
56 ros::Time stamp_;
57 double posDes_{}, velDes_{}, kp_{}, kd_{}, ff_{};
58};
59
60struct ImuData
61{
62 gazebo::physics::LinkPtr link_ptr;
63 ros::Time time_stamp;
64 double ori[4];
65 double ori_cov[9];
66 double angular_vel[3];
67 double angular_vel_cov[9];
68 double linear_acc[3];
69 double linear_acc_cov[9];
70};
71
72class RmRobotHWSim : public gazebo_ros_control::DefaultRobotHWSim
73{
74public:
75 bool initSim(const std::string& robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model,
76 const urdf::Model* urdf_model,
77 std::vector<transmission_interface::TransmissionInfo> transmissions) override;
78 void readSim(ros::Time time, ros::Duration period) override;
79 void writeSim(ros::Time time, ros::Duration period) override;
80
81private:
82 void parseImu(XmlRpc::XmlRpcValue& imu_datas, const gazebo::physics::ModelPtr& parent_model);
83
84 static bool switchImuStatus(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
85 {
86 disable_imu_ = !disable_imu_;
87 res.success = true;
88 std::string imu_status_message = disable_imu_ ? "disable" : "enable";
89 res.message = "Imu status: " + imu_status_message;
90 return true;
91 }
92
93 rm_control::HybridJointInterface hybridJointInterface_;
94 rm_control::RobotStateInterface robot_state_interface_;
95 hardware_interface::ImuSensorInterface imu_sensor_interface_;
96 rm_control::RmImuSensorInterface rm_imu_sensor_interface_;
97 gazebo::physics::WorldPtr world_;
98 std::list<ImuData> imu_datas_;
99 ros::ServiceServer switch_imu_service_;
100
101 std::list<HybridJointData> hybridJointDatas_;
102 std::unordered_map<std::string, std::deque<HybridJointCommand> > cmdBuffer_;
103
104 static bool disable_imu_;
105 double delay_{};
106};
107
108} // namespace rm_gazebo
Definition hybrid_joint_interface.h:113
Definition rm_imu_sensor_interface.h:36
Definition robot_state_interface.h:93
Definition rm_robot_hw_sim.h:73
bool initSim(const std::string &robot_namespace, ros::NodeHandle model_nh, gazebo::physics::ModelPtr parent_model, const urdf::Model *urdf_model, std::vector< transmission_interface::TransmissionInfo > transmissions) override
Definition rm_robot_hw_sim.cpp:44
void writeSim(ros::Time time, ros::Duration period) override
Definition rm_robot_hw_sim.cpp:117
void readSim(ros::Time time, ros::Duration period) override
Definition rm_robot_hw_sim.cpp:75
Definition rm_robot_hw_sim.h:47
Definition rm_robot_hw_sim.h:55
double kd_
Definition rm_robot_hw_sim.h:57
double ff_
Definition rm_robot_hw_sim.h:57
double kp_
Definition rm_robot_hw_sim.h:57
double velDes_
Definition rm_robot_hw_sim.h:57
double posDes_
Definition rm_robot_hw_sim.h:57
ros::Time stamp_
Definition rm_robot_hw_sim.h:56
Definition rm_robot_hw_sim.h:49
double kp_
Definition rm_robot_hw_sim.h:51
double velDes_
Definition rm_robot_hw_sim.h:51
double posDes_
Definition rm_robot_hw_sim.h:51
double kd_
Definition rm_robot_hw_sim.h:51
double ff_
Definition rm_robot_hw_sim.h:51
hardware_interface::JointHandle joint_
Definition rm_robot_hw_sim.h:50
Definition rm_robot_hw_sim.h:61
double linear_acc[3]
Definition rm_robot_hw_sim.h:68
ros::Time time_stamp
Definition rm_robot_hw_sim.h:63
double ori[4]
Definition rm_robot_hw_sim.h:64
double angular_vel[3]
Definition rm_robot_hw_sim.h:66
double angular_vel_cov[9]
Definition rm_robot_hw_sim.h:67
double ori_cov[9]
Definition rm_robot_hw_sim.h:65
gazebo::physics::LinkPtr link_ptr
Definition rm_robot_hw_sim.h:62
double linear_acc_cov[9]
Definition rm_robot_hw_sim.h:69