|
Package Summary
Tags | No category tags. |
Version | 0.1.11 |
License | BSD |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/rm-controls/rm_controllers.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-11-23 |
Dev Status | DEVELOPED |
CI status | Continuous Integration : 0 / 0 |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Qiayuan Liao
Authors
- Qiayuan Liao
rm_gimbal_controllers
Overview
The rm_gimbal_controllers has three states: RATE, TRACK, and DIRECT. It performs PID control on the yaw joint and pitch joint according to commands. It can also perform moving average filtering based on detection data and calculate, predict and track targets based on the ballistic model.
Keywords: ROS, Robomaster, gimbal, bullet solver, moving average filter
License
The source code is released under a BSD 3-Clause license.
Author: DynamicX
Affiliation: DynamicX
Maintainer: DynamicX
The package has been tested under ROS Indigo, Melodic and Noetic on respectively Ubuntu 18.04 and 20.04. This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed.
Hardware interface type
-
JointStateInterface
Used to get the speed and position of gimbal joint. -
EffortJointInterface
Used to send effort command to gimbal joint . -
RoboStateInterface
Used to get the current and historical transform between gimbal and the world coordinate system and the transform between visual target and the world coordinate system.
Installation
Installation from Packages
To install all packages from the this repository as Debian packages use
sudo apt-get install ros-noetic-rm-gimbal-controllers
Or better, use rosdep
:
sudo rosdep install --from-paths src
Dependencies
- roscpp
- rm_common
- effort_controllers
- tf2_eigen
- tf2_geometry_msgs
- visualization_msgs
- dynamic_reconfigure
ROS API
Subscribed Topics
-
command
(rm_msgs/GimbalCmd)Set gimbal mode, pitch and yaw axis rotation speed, tracking target, pointing target and coordinate system.
-
/detection
(rm_msgs/TargetDetectionArray)Receive visual recognition data.
-
/<camera_name>/camera_info
(CameraInfo)Make sure that the detection node receives a new frame of image and sends the prediction data to the detection node.
Published Topics
-
error
(rm_msgs/GimbalDesError) The error calculated by the ballistic model to shoot at the current gimbal angle to the target. -
track
(rm_msgs/TrackDataArray) The predicted data used for detection node to decide the ROI.Bullet solver
-
model_desire
( visualization_msgs/Marker ) Used to visualize the desired bullet trajectory. -
model_real
( visualization_msgs/Marker ) Used to visualize the trajectory that caculated by ballistic model in the current gimbal angle.Parameters
-
detection_topic
(string, default: “/detection”)The name of the topic where detection node gets predicted data.
-
detection_frame
(string, default: “detection”)The name of the frame of detection.
-
camera_topic
(string, default: “/galaxy_camera/camera_info”)The name of the topic that is determined that the detection node receives a new frame of image and sends the prediction data to the detection node.
-
publish_rate
(double)Frequency (in Hz) of publishing gimbal error.
-
chassis_angular_data_num
(double)The number of angle data of chassis.Used for chassis angular average filter.
-
time_compensation
(double)Time(in s) of image transmission delay(in s).Used to compensate for the effects of images transimission delay
Bullet solver
Bullet solver is used to get the bullet drop point
-
resistance_coff_qd_10, resistance_coff_qd_15, resistance_coff_qd_16, resistance_coff_qd_18, resistance_coff_qd_30
(double
)The air resistance coefficient used for bullet solver when bullet speed is 10 m/s, 15 m/s, 16 m/s, 18 m/s and 30 m/s.
-
g
(double)Acceleration of gravity.
-
delay
(double)Shooting delay time(in s) after shooter get the shooting command.Used to compensate for the effects of launch delay.
-
timeout
(double)Timeout time((in s)) of bullet solver.Used to judge whether bullet solver can caculate the bullet drop point.
Moving average filter
Moving average filter is used for filter the target armor center when target is spin.
-
is_debug
(bool
, default: true )The debug status.When it is true, debug data will be pulished on the filter topic.
-
pos_data_num
(double, default: 20)The number of armor position data.
-
vel_data_num
(double, default: 30)The number of armor linear velocity data.
-
gyro_data_num
(double, default: 100)The number of target rotation speed data.
-
center_data_num
(double, default: 50)The number of target rotation center position data.
-
center_offset_z
(double)Offset(in meter) on the z axis.Used to compensate for the error of filter result on z axis.
Controller configuration examples
gimbal_controller:
type: rm_gimbal_controllers/Controller
time_compensation: 0.03
publish_rate: 100
chassis_angular_data_num: 20
camera_topic: "/galaxy_camera/camera_info"
yaw:
joint: "yaw_joint"
pid: { p: 8, i: 0, d: 0.4, i_clamp_max: 0.0, i_clamp_min: -0.0, antiwindup: true, publish_state: true }
pitch:
joint: "pitch_joint"
pid: { p: 10, i: 50, d: 0.3, i_clamp_max: 0.4, i_clamp_min: -0.4, antiwindup: true, publish_state: true }
bullet_solver:
resistance_coff_qd_10: 0.45
resistance_coff_qd_15: 0.1
resistance_coff_qd_16: 0.7
resistance_coff_qd_18: 0.55
resistance_coff_qd_30: 3.0
g: 9.81
delay: 0.1
dt: 0.001
timeout: 0.001
publish_rate: 50
moving_average_filter:
is_debug: true
center_offset_z: 0.05
pos_data_num: 20
vel_data_num: 30
center_data_num: 50
gyro_data_num: 100
Bugs & Feature Requests
Please report bugs and request features using the Issue Tracker.
Changelog for package rm_gimbal_controllers
0.1.11 (2023-06-20)
- Merge pull request #135 from ye-luo-xi-tui/feedforward Add input feedforward and fix a bug in computing desire vel at TRACK mode
- Add input feedforward and fix a bug in computing desire vel at TRACK mode.
- Merge pull request #124 from ye-luo-xi-tui/resistance_compensation Add velocity_dead_zone and effort_dead_zone
- Merge branch 'master' into dev/balance
- Add velocity_dead_zone and effort_dead_zone.
- Merge pull request #120 from ye-luo-xi-tui/master 0.1.10
- Merge branch 'rm-controls:master' into gpio_calibration_controller
- Contributors: 1moule, ye-luo-xi-tui, yezi, yuchen
0.1.10 (2023-03-25)
- Merge branch 'rm-controls:master' into master
- Merge pull request #114 from ye-luo-xi-tui/resistance_compensation Add resistance compensation on yaw
- Add resistance compensation on yaw.
- Merge pull request #113 from ye-luo-xi-tui/master Use Vector3WithFilter in rm_common instead
- Use Vector3WithFilter in rm_common instead.
- Merge pull request #106 from ye-luo-xi-tui/master 0.1.9
- Contributors: ye-luo-xi-tui, yezi
0.1.9 (2023-02-21)
- Merge pull request #104 from ye-luo-xi-tui/balance_standard Fix bug.
- Fix bug.
- Merge pull request #102 from ljq-lv/fix_warning Fixed the bug of gimbal warning
- Add the else to judge mode TRACK
- Fixed the bug of gimbal warning
- Merge branch 'master' into balance_standard
- Merge pull request #97 from ye-luo-xi-tui/master 0.1.8
- Contributors: ljq-lv, ye-luo-xi-tui, yezi
0.1.8 (2022-11-24)
- Merge pull request #92 from ye-luo-xi-tui/target_velocity_correction Estimate chassis vel with moving average and subtract chassis_vel from target_vel
- Fix trylock bug.
- Subtract chassis_vel from target_vel.
- Estimate chassis vel with moving average.
- Merge pull request #86 from NaHCO3bc/Readme Fix the dependence part bug.
- Modify the test file folder.
- Fix the dependence part bug.
- Merge pull request #85 from ye-luo-xi-tui/master 0.1.7
- Contributors: NaHCO3bc, ye-luo-xi-tui, yezi
0.1.7 (2022-09-10)
- Optimize TRACK mode of rm_gimbal_controller.
- Change frame "map" to "odom".
- Merge remote-tracking branch 'origin/master'
- Contributors: qiayuan, yezi
0.1.6 (2022-06-16)
- Merge branch 'gimbal/chassis_vel'
- Merge pull request #77 from ye-luo-xi-tui/gimbal/chassis_vel Fix a stupid bug
- Fix a stupid bug.
- Add chassis_vel as a feedforward to the yaw joint
- Merge remote-tracking branch 'origin/master'
- Add chassis_vel to yaw's PID
- Contributors: QiayuanLiao, qiayuan, yezi
0.1.5 (2022-06-10)
- Merge pull request #71 from ye-luo-xi-tui/gimbal/joint_velocity Set joint desired velocity according to the target velocity
- Fix a bug in setting joint desired velocity.
- Set joint desired velocity according to the target velocity.
- Merge pull request #69 from ChenZheng29/master Correct track topic message type:TrackData
- Merge remote-tracking branch 'origin/master'
- Merge pull request #66 from ye-luo-xi-tui/master Use motors' data in pid controller when imu_name isn't set
- Use motors' data in pid controller when imu_name isn't set.
- Correct the message type of gimbal subscription '/track' topic from 'rm_msgs::TrackCmd' to 'rm_msgs::TrackData'
- Modify the track topic name and message, and unify the track interface
- Merge remote-tracking branch 'origin/master'
- 0.1.4
- Move all computation in gimbal_controller i.r.t. "odom" instead of "map"
- Merge pull request #52 from ye-luo-xi-tui/gimbal_track Update gimbal_controller
- Modifier TrackCmd.msg format.
- Improve logic of function Controller::setDes().
- Fix a frame error in track mode.
- Merge branch 'master' into gimbal_track
- Merge pull request #45 from mlione/master Delete some config files in rm_controllers.
- Delete some config files in rm_controller.
- Merge pull request #46 from ye-luo-xi-tui/master Deprecated imu_filter_controller
- Merge branch 'master' into gimbal_track
- Rename a msg.
- Modifier track subscribe topic
- Contributors: QiayuanLiao, YuuinIH, chenzheng, mlione, qiayuan, yezi
0.1.3 (2022-03-28)
- Merge pull request #42 from ye-luo-xi-tui/fix_gimbal Fix bug in gimbal_controller
- Merge pull request #37 from ye-luo-xi-tui/forward_feed Add feedforward in gimbal control
- Merge branch 'master' into forward_feed
- Simplify the codes. Set vel_target under rate mode.
- Fix bug which relative to limit in gimbal_controller.
- Merge pull request #40 from ye-luo-xi-tui/maintain Delete configuration of robot_state_controller in each of controllers' config file
- Merge branch 'master' into 'standard3'.
- Merge branch 'master' into maintain # Conflicts: # rm_chassis_controllers/config/standard3.yaml # rm_chassis_controllers/config/standard4.yaml
- Delete configuration of robot_state_controller in each of controllers' config file
- Merge branch 'master' into standard3
- Delete eigen, tf2_eigen instead.
- chore: add missing deps
- Merge remote-tracking branch 'origin/master'
- Change frame id of gimbal while transforming angular_vel form imu to pitch/yaw for engineer or sentry.
- Add feedforward in gimbal control.
- Contributors: QiayuanLiao, StarHeart, qiayuan, ye-luo-xi-tui, yezi
0.1.2 (2022-01-08)
- Merge pull request #30 from ljq-lv/rm_gimbal_controllers Modify namespace on rm_gimbal_controllers
- Modify namespace from bullet_solver to rm_gimbal_controllers
- Merge branch 'master' into omni_wheel_controller
- Merge remote-tracking branch 'origin/master'
- Merge branch 'rm-controls:master' into master
- Merge branch 'rm-controls:master' into master
- Merge pull request #17 from ChenZheng29/master Fix the abnormal gimbal caused by the different representation of angle between TF and URDF
- Merge branch 'master' of https://github.com/YuuinIH/rm_controllers
- Add the judgment of the pitch of the gimbal
- Fix gimbal position limit
- Merge branch 'gimbal/opti_or_simplify' into chassis/balance_imu_interface
- Update the config of rm_gimbal_controllers, load only one controller on launch instead of spawn controllers
- Merge branch 'gimbal/opti_or_simplify' into imu_filter_controllers
- Test imu2can with gimbal, fix a stupid bug
- Rename standard to gimbal_base
- Correct format.
- Merge branch 'master' into chassis/fix_filter
- Merge remote-tracking branch 'origin/master'
- Update static_transform_publisher from tf to tf2
- Remove updateTf() of rm_gimbal_controllers
- Fix tf time of rm_gimbal_controllers
- Use gyro data as gimbal joint velocity.
- Sort code, add imu_sensor_interface
- Simplify rm_gimbal_controllers and tested on gazebo
- Modified GimbalCmd.msg, and delete moving_average_filter
- Merge branch 'namespace' # Conflicts: # rm_chassis_controllers/README.md
- Merge pull request #15 from ye-luo-xi-tui/namespace Change name of namespace:from hardware_interface to rm_control
- Correct format
- Change name of namespace:from hardware_interface to rm_control.
- Merge pull request #5 from BruceLannn/master Reformat gimbal controllers' README.md
- Update publish rate description.
- Update the command of installing shooter controller.
- Update publish rate description.
- Correct GimbanlCmd to GimbalCmd and delet ##cfg
- Update model_desire topic description.
- Correct a format error.
- Add model_desire and model_real description in the published topic.
- Update cfg file description.
- Correct param type format.
- Update moving average filter's param.
- Update some param's description.
- Supplementary unit of center_offset_z.
- Update parameter's description.
- Use “pragma once” in rm_gimbal_controllers headers instead of include guards.
- Update Overview's keywords.
- Update Overview.
- Reformat README.md
- Update shooter param's description.
- Correct readme format.
- Correct readme format.
- Correct readme format.
- Update controllers README.
- Update controllers README.
- Fix wrong naming "include/rm_gimbal_controller"
- Run pre-commit
- Code style
- Format rm_gimbal_controllers using clang-format
- Contributors: BruceLannn, QiayuanLiao, YuuinIH, chenzheng, kbxkgxjg, qiayuan, ye-luo-xi-tui, yezi
0.1.1 (2021-08-12)
- Set all version to the same
- Add license to rm_chassis_controllers and rm_gimbal_controllers source files
- Add add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg)
- Merge remote-tracking branch 'alias_memory/metapackage'
- Move all files to rm_gimbal_controllers/rm_gimbal_controllers, prepare for merge
- Contributors: qiayuan
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
catkin | |
roscpp | |
rm_common | |
controller_interface | |
effort_controllers | |
tf2_eigen | |
tf2_geometry_msgs | |
visualization_msgs | |
dynamic_reconfigure | |
angles |
System Dependencies
Dependant Packages
Name | Deps |
---|---|
rm_controllers |
Launch files
- test/load_controllers.launch
-
- base_link_tf [default: false] — Set true when not imu and chassis controllers loaded
- odom_tf [default: false] — Set true when not chassis but imu and orientation controllers loaded