gimbal_base.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 1/16/21.
36 //
37 
38 #pragma once
39 
46 #include <rm_msgs/GimbalCmd.h>
47 #include <rm_msgs/TrackData.h>
48 #include <rm_msgs/GimbalDesError.h>
49 #include <rm_msgs/GimbalPosState.h>
50 #include <rm_gimbal_controllers/GimbalBaseConfig.h>
52 #include <tf2_eigen/tf2_eigen.h>
53 #include <Eigen/Eigen>
54 #include <control_toolbox/pid.h>
55 #include <urdf/model.h>
56 #include <dynamic_reconfigure/server.h>
58 #include <unordered_map>
59 
60 namespace rm_gimbal_controllers
61 {
62 struct GimbalConfig
63 {
65  double accel_pitch_{}, accel_yaw_{};
66 };
67 
68 class ChassisVel
69 {
70 public:
71  ChassisVel(const ros::NodeHandle& nh)
72  {
73  double num_data;
74  nh.param("num_data", num_data, 20.0);
75  nh.param("debug", is_debug_, true);
76  linear_ = std::make_shared<Vector3WithFilter<double>>(num_data);
77  angular_ = std::make_shared<Vector3WithFilter<double>>(num_data);
78  if (is_debug_)
79  {
82  }
83  }
84  std::shared_ptr<Vector3WithFilter<double>> linear_;
85  std::shared_ptr<Vector3WithFilter<double>> angular_;
86  void update(double linear_vel[3], double angular_vel[3], double period)
87  {
88  if (period < 0)
89  return;
90  if (period > 0.1)
91  {
92  linear_->clear();
93  angular_->clear();
94  }
95  linear_->input(linear_vel);
96  angular_->input(angular_vel);
97  if (is_debug_ && loop_count_ % 10 == 0)
98  {
99  if (real_pub_->trylock())
100  {
101  real_pub_->msg_.linear.x = linear_vel[0];
102  real_pub_->msg_.linear.y = linear_vel[1];
103  real_pub_->msg_.linear.z = linear_vel[2];
104  real_pub_->msg_.angular.x = angular_vel[0];
105  real_pub_->msg_.angular.y = angular_vel[1];
106  real_pub_->msg_.angular.z = angular_vel[2];
107 
108  real_pub_->unlockAndPublish();
109  }
110  if (filtered_pub_->trylock())
111  {
112  filtered_pub_->msg_.linear.x = linear_->x();
113  filtered_pub_->msg_.linear.y = linear_->y();
114  filtered_pub_->msg_.linear.z = linear_->z();
115  filtered_pub_->msg_.angular.x = angular_->x();
116  filtered_pub_->msg_.angular.y = angular_->y();
117  filtered_pub_->msg_.angular.z = angular_->z();
118 
119  filtered_pub_->unlockAndPublish();
120  }
121  }
122  loop_count_++;
123  }
124 
125 private:
126  bool is_debug_;
128  std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::Twist>> real_pub_{}, filtered_pub_{};
129 };
130 
131 class Controller : public controller_interface::MultiInterfaceController<rm_control::RobotStateInterface,
132  hardware_interface::ImuSensorInterface,
133  hardware_interface::EffortJointInterface>
134 {
135 public:
136  Controller() = default;
137  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
138  void starting(const ros::Time& time) override;
139  void update(const ros::Time& time, const ros::Duration& period) override;
140  void setDes(const ros::Time& time, double yaw_des, double pitch_des);
141 
142 private:
143  void rate(const ros::Time& time, const ros::Duration& period);
144  void track(const ros::Time& time);
145  void direct(const ros::Time& time);
146  void traj(const ros::Time& time);
147  bool setDesIntoLimit(const tf2::Quaternion& base2gimbal_des, const urdf::JointConstSharedPtr& joint_urdf,
148  tf2::Quaternion& base2new_des);
149  void moveJoint(const ros::Time& time, const ros::Duration& period);
150  void updateChassisVel();
151  double feedForward(const ros::Time& time);
152  double updateCompensation(double chassis_vel_angular_z);
153  void commandCB(const rm_msgs::GimbalCmdConstPtr& msg);
154  void trackCB(const rm_msgs::TrackDataConstPtr& msg);
155  void reconfigCB(rm_gimbal_controllers::GimbalBaseConfig& config, uint32_t);
156  std::string getGimbalFrameID(std::unordered_map<int, urdf::JointConstSharedPtr> joint_urdfs);
157  std::string getBaseFrameID(std::unordered_map<int, urdf::JointConstSharedPtr> joint_urdfs);
158 
161  std::unordered_map<int, std::unique_ptr<effort_controllers::JointVelocityController>> ctrls_;
162  std::unordered_map<int, std::unique_ptr<control_toolbox::Pid>> pid_pos_;
163  std::unordered_map<int, urdf::JointConstSharedPtr> joint_urdfs_;
164  std::unordered_map<int, bool> pos_des_in_limit_;
165  bool has_imu_ = true;
166 
167  std::shared_ptr<BulletSolver> bullet_solver_;
168 
169  // ROS Interface
171  std::unordered_map<int, std::unique_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalPosState>>> pos_state_pub_;
172  std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalDesError>> error_pub_;
177 
178  rm_msgs::GimbalCmd cmd_gimbal_;
179  rm_msgs::TrackData data_track_;
180  std::string gimbal_des_frame_id_{}, imu_name_{};
181  double publish_rate_{};
182  bool state_changed_{};
183  int loop_count_{};
184 
185  // Transform
186  geometry_msgs::TransformStamped odom2gimbal_des_, odom2gimbal_, odom2base_, last_odom2base_;
187 
188  // Gravity Compensation
189  geometry_msgs::Vector3 mass_origin_;
190  double gravity_;
192 
193  // Chassis
194  std::shared_ptr<ChassisVel> chassis_vel_;
196 
200  dynamic_reconfigure::Server<rm_gimbal_controllers::GimbalBaseConfig>* d_srv_{};
201 
202  enum
203  {
208  };
209  int state_ = RATE;
210  bool start_ = false;
211 };
212 
213 } // namespace rm_gimbal_controllers
rm_gimbal_controllers::Controller::has_imu_
bool has_imu_
Definition: gimbal_base.h:196
realtime_tools::RealtimeBuffer< rm_msgs::GimbalCmd >
rm_gimbal_controllers::Controller::RATE
@ RATE
Definition: gimbal_base.h:235
rm_gimbal_controllers::Controller::updateChassisVel
void updateChassisVel()
Definition: gimbal_base.cpp:567
realtime_publisher.h
rm_gimbal_controllers::Controller::odom2gimbal_
geometry_msgs::TransformStamped odom2gimbal_
Definition: gimbal_base.h:217
rm_gimbal_controllers::Controller::setDesIntoLimit
bool setDesIntoLimit(const tf2::Quaternion &base2gimbal_des, const urdf::JointConstSharedPtr &joint_urdf, tf2::Quaternion &base2new_des)
Definition: gimbal_base.cpp:398
rm_gimbal_controllers::Controller::track
void track(const ros::Time &time)
Definition: gimbal_base.cpp:270
rm_gimbal_controllers::ChassisVel::update
void update(double linear_vel[3], double angular_vel[3], double period)
Definition: gimbal_base.h:117
rm_gimbal_controllers::Controller::start_
bool start_
Definition: gimbal_base.h:241
rm_gimbal_controllers::Controller::track_rt_buffer_
realtime_tools::RealtimeBuffer< rm_msgs::TrackData > track_rt_buffer_
Definition: gimbal_base.h:207
rm_gimbal_controllers::Controller::data_track_sub_
ros::Subscriber data_track_sub_
Definition: gimbal_base.h:205
rm_gimbal_controllers::Controller::traj
void traj(const ros::Time &time)
Definition: gimbal_base.cpp:367
rm_gimbal_controllers::Controller::config_rt_buffer_
realtime_tools::RealtimeBuffer< GimbalConfig > config_rt_buffer_
Definition: gimbal_base.h:230
rm_gimbal_controllers::ChassisVel::loop_count_
int loop_count_
Definition: gimbal_base.h:158
tf2_eigen.h
rm_gimbal_controllers::Controller::last_publish_time_
ros::Time last_publish_time_
Definition: gimbal_base.h:201
rm_gimbal_controllers::GimbalConfig
Definition: gimbal_base.h:93
rm_gimbal_controllers::Controller::joint_urdfs_
std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs_
Definition: gimbal_base.h:194
rm_gimbal_controllers::Controller::ctrls_
std::unordered_map< int, std::unique_ptr< effort_controllers::JointVelocityController > > ctrls_
Definition: gimbal_base.h:192
rm_control::RobotStateHandle
joint_velocity_controller.h
rm_gimbal_controllers::Controller::chassis_vel_
std::shared_ptr< ChassisVel > chassis_vel_
Definition: gimbal_base.h:225
filters.h
rm_gimbal_controllers::Controller::d_srv_
dynamic_reconfigure::Server< rm_gimbal_controllers::GimbalBaseConfig > * d_srv_
Definition: gimbal_base.h:231
rm_gimbal_controllers::Controller::state_
int state_
Definition: gimbal_base.h:240
rm_gimbal_controllers::Controller::getBaseFrameID
std::string getBaseFrameID(std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs)
Definition: gimbal_base.cpp:598
rm_gimbal_controllers::Controller::starting
void starting(const ros::Time &time) override
Definition: gimbal_base.cpp:189
rm_gimbal_controllers::Controller::enable_gravity_compensation_
bool enable_gravity_compensation_
Definition: gimbal_base.h:222
rm_gimbal_controllers::Controller::imu_name_
std::string imu_name_
Definition: gimbal_base.h:211
rm_gimbal_controllers::Controller::moveJoint
void moveJoint(const ros::Time &time, const ros::Duration &period)
Definition: gimbal_base.cpp:425
rm_gimbal_controllers::Controller::rate
void rate(const ros::Time &time, const ros::Duration &period)
Definition: gimbal_base.cpp:248
rm_gimbal_controllers::Controller::gimbal_des_frame_id_
std::string gimbal_des_frame_id_
Definition: gimbal_base.h:211
imu_sensor_interface.h
rm_gimbal_controllers::Controller::publish_rate_
double publish_rate_
Definition: gimbal_base.h:212
rm_gimbal_controllers::Controller::cmd_gimbal_sub_
ros::Subscriber cmd_gimbal_sub_
Definition: gimbal_base.h:204
rm_gimbal_controllers::Controller::updateCompensation
double updateCompensation(double chassis_vel_angular_z)
Definition: gimbal_base.cpp:609
realtime_tools::RealtimePublisher
rm_gimbal_controllers::Controller::DIRECT
@ DIRECT
Definition: gimbal_base.h:237
rm_gimbal_controllers::Controller::mass_origin_
geometry_msgs::Vector3 mass_origin_
Definition: gimbal_base.h:220
joint_command_interface.h
rm_gimbal_controllers::Controller::loop_count_
int loop_count_
Definition: gimbal_base.h:214
rm_gimbal_controllers::ChassisVel::ChassisVel
ChassisVel(const ros::NodeHandle &nh)
Definition: gimbal_base.h:102
rm_gimbal_controllers::Controller::trackCB
void trackCB(const rm_msgs::TrackDataConstPtr &msg)
Definition: gimbal_base.cpp:622
hardware_interface::RobotHW
rm_gimbal_controllers::ChassisVel::filtered_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > filtered_pub_
Definition: gimbal_base.h:159
rm_gimbal_controllers::GimbalConfig::accel_yaw_
double accel_yaw_
Definition: gimbal_base.h:127
controller_interface::MultiInterfaceController
model.h
rm_gimbal_controllers::Controller::robot_state_handle_
rm_control::RobotStateHandle robot_state_handle_
Definition: gimbal_base.h:190
rm_gimbal_controllers
Definition: bullet_solver.h:54
rm_gimbal_controllers::GimbalConfig::chassis_comp_d_
double chassis_comp_d_
Definition: gimbal_base.h:126
rm_gimbal_controllers::GimbalConfig::yaw_k_v_
double yaw_k_v_
Definition: gimbal_base.h:126
rm_gimbal_controllers::Controller::odom2gimbal_des_
geometry_msgs::TransformStamped odom2gimbal_des_
Definition: gimbal_base.h:217
rm_gimbal_controllers::Controller::cmd_rt_buffer_
realtime_tools::RealtimeBuffer< rm_msgs::GimbalCmd > cmd_rt_buffer_
Definition: gimbal_base.h:206
rm_gimbal_controllers::GimbalConfig::chassis_comp_a_
double chassis_comp_a_
Definition: gimbal_base.h:126
rm_gimbal_controllers::GimbalConfig::chassis_comp_b_
double chassis_comp_b_
Definition: gimbal_base.h:126
rm_gimbal_controllers::GimbalConfig::chassis_comp_c_
double chassis_comp_c_
Definition: gimbal_base.h:126
rm_gimbal_controllers::Controller::pid_pos_
std::unordered_map< int, std::unique_ptr< control_toolbox::Pid > > pid_pos_
Definition: gimbal_base.h:193
rm_gimbal_controllers::Controller::Controller
Controller()=default
rm_gimbal_controllers::Controller::error_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::GimbalDesError > > error_pub_
Definition: gimbal_base.h:203
hardware_interface::ImuSensorHandle
robot_state_interface.h
rm_gimbal_controllers::Controller::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: gimbal_base.cpp:80
rm_gimbal_controllers::Controller::TRACK
@ TRACK
Definition: gimbal_base.h:236
rm_gimbal_controllers::Controller::dynamic_reconfig_initialized_
bool dynamic_reconfig_initialized_
Definition: gimbal_base.h:228
rm_gimbal_controllers::Controller::imu_sensor_handle_
hardware_interface::ImuSensorHandle imu_sensor_handle_
Definition: gimbal_base.h:191
rm_gimbal_controllers::Controller::TRAJ
@ TRAJ
Definition: gimbal_base.h:238
ros::Time
rm_gimbal_controllers::Controller::bullet_solver_
std::shared_ptr< BulletSolver > bullet_solver_
Definition: gimbal_base.h:198
rm_gimbal_controllers::Controller::odom2base_
geometry_msgs::TransformStamped odom2base_
Definition: gimbal_base.h:217
rm_gimbal_controllers::Controller::pos_des_in_limit_
std::unordered_map< int, bool > pos_des_in_limit_
Definition: gimbal_base.h:195
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
rm_gimbal_controllers::Controller::feedForward
double feedForward(const ros::Time &time)
Definition: gimbal_base.cpp:545
rm_gimbal_controllers::ChassisVel::linear_
std::shared_ptr< Vector3WithFilter< double > > linear_
Definition: gimbal_base.h:115
rm_gimbal_controllers::ChassisVel::real_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > real_pub_
Definition: gimbal_base.h:159
pid.h
rm_gimbal_controllers::Controller::data_track_
rm_msgs::TrackData data_track_
Definition: gimbal_base.h:210
rm_gimbal_controllers::GimbalConfig::accel_pitch_
double accel_pitch_
Definition: gimbal_base.h:127
rm_gimbal_controllers::Controller::commandCB
void commandCB(const rm_msgs::GimbalCmdConstPtr &msg)
Definition: gimbal_base.cpp:617
rm_gimbal_controllers::ChassisVel::angular_
std::shared_ptr< Vector3WithFilter< double > > angular_
Definition: gimbal_base.h:116
rm_gimbal_controllers::Controller::config_
GimbalConfig config_
Definition: gimbal_base.h:229
rm_gimbal_controllers::Controller::chassis_compensation_
double chassis_compensation_
Definition: gimbal_base.h:226
rm_gimbal_controllers::Controller::cmd_gimbal_
rm_msgs::GimbalCmd cmd_gimbal_
Definition: gimbal_base.h:209
rm_gimbal_controllers::Controller::pos_state_pub_
std::unordered_map< int, std::unique_ptr< realtime_tools::RealtimePublisher< rm_msgs::GimbalPosState > > > pos_state_pub_
Definition: gimbal_base.h:202
rm_gimbal_controllers::Controller::last_odom2base_
geometry_msgs::TransformStamped last_odom2base_
Definition: gimbal_base.h:217
ros::Duration
rm_gimbal_controllers::Controller::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: gimbal_base.cpp:196
rm_gimbal_controllers::Controller::setDes
void setDes(const ros::Time &time, double yaw_des, double pitch_des)
Definition: gimbal_base.cpp:235
rm_gimbal_controllers::Controller::getGimbalFrameID
std::string getGimbalFrameID(std::unordered_map< int, urdf::JointConstSharedPtr > joint_urdfs)
Definition: gimbal_base.cpp:587
rm_gimbal_controllers::Controller::direct
void direct(const ros::Time &time)
Definition: gimbal_base.cpp:340
rm_gimbal_controllers::Controller::gravity_
double gravity_
Definition: gimbal_base.h:221
rm_gimbal_controllers::ChassisVel::is_debug_
bool is_debug_
Definition: gimbal_base.h:157
bullet_solver.h
ros::NodeHandle
ros::Subscriber
rm_gimbal_controllers::Controller::state_changed_
bool state_changed_
Definition: gimbal_base.h:213
rm_gimbal_controllers::Controller::reconfigCB
void reconfigCB(rm_gimbal_controllers::GimbalBaseConfig &config, uint32_t)
Definition: gimbal_base.cpp:629
rm_gimbal_controllers::GimbalConfig::pitch_k_v_
double pitch_k_v_
Definition: gimbal_base.h:126
multi_interface_controller.h


rm_gimbal_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:21