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-03-04
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

RoboMaster standard robot Chassis controller

Additional Links

No additional links.

Maintainers

  • Qiayuan Liao

Authors

  • Qiayuan Liao

rm_chassis_controllers

Overview

There are three states: raw, follow and twist. The output torque and speed of each motor of the chassis can be calculated according to the current state of the control, the received speed and pose of the pan/tilt, and the speed and acceleration commands, and the data is returned by the motor to calculate The speed and posture of the chassis are released. The control algorithm involved in the chassis controller is PID algorithm.

Keywords: mecanum, swerve, balance, chassis, ROS, RoboMaster

Hardware interface type

  • JointStateInterface Used to get the position and speed of chassis wheel joint.

  • EffortJointInterface Used to send the torque command of chassis wheel joint.

  • RoboSateInterface Used for high-frequency maintenance of the transformation relationship of changing odom to base_link.

Installation

Installation from Packages

To install all packages from the this repository as Debian packages use

sudo apt-get install ros-noetic-rm-chassis-controllers

Or better, use rosdep:

sudo rosdep install --from-paths src

Dependencies

  • Robot Operating System (ROS) (middleware for robotics),
  • roscpp
  • rm_common
  • controller_interface
  • effort_controllers
  • tf2_geometry_msgs
  • angles
  • robot_localization

ROS API

Subscribed Topics

The inertial measurement unit data of base command.

  • command (rm_msgs::ChassisCmd)

Set the mode, acceleration, and maximum power of the chassis.

Set the speed of the chassis.

Published Topics

Chassis odometer information (speed, position, covariance).

Contains quantities of state and control about the Balance.

Parameters

common
  • wheel_radius (double)

Radius of the wheels.

  • wheel_track (double)

The distance between the center of the left and right wheels on the same side.

  • wheel_base (double)

The distance between the center of the front and rear wheels on the same side.

  • twist_angle (double)

Amplitude of twist at twist state.

  • enable_odom_tf (bool, default: true)

Option.If it is set to true, it will store Transform in tf_buffer.

  • publish_odom_tf_ (bool, default: false)

Option.If it is set to true, enable_odom_tf is also true, it will send Transform from odom to base.

  • twist_covariance_diagonal (double[6])

The diagonal covariance matrix of twist.

  • publish_rate (double, default: 50)

Frequency (in Hz) of publishing Transform.

  • coeff (double)

A coefficient. Adjust this coefficient to reduce the impact of power loss.

  • min_vel (double)

The minimum velocity of chassis joint which is used to calculate the max torque.

  • timeout (double)

Allowed period (in s) between two commands. If the time is exceed this period, the speed of chassis will be set 0.

  • power_offset (double)

Fix the difference between theoretical power and actual power.

Balance
  • imu_name (string, default: "base_imu")

Chassis imu name.

  • left/wheel_joint (string, default: "left_wheel_joint")

left wheel joint name.

  • left/block_joint (string, default: "left_momentum_block_joint")

left momentum block joint name.

  • right/wheel_joint (string, default: "right_wheel_joint")

right wheel joint name.

  • right/block_joint (string, default: "right_momentum_block_joint")

right momentum block joint name.

  • m_w (double, default: 0.72)

mass of single wheel.

  • m (double, default: 11.48)

mass of the robot except wheels and momentum_blocks.

  • m_b (double, default: 1.13)

mass of single momentum_block.

  • i_w (double, default: 0.01683)

The moment of inertia of the wheel around the rotational axis of the motor.

  • l (double, default: 0.0587)

The vertical component of the distance between the wheel center and the center of mass of robot.

  • y_b (double, default: 0.16)

The y-axis component of the coordinates of the momentum block in the base_link coordinate system.

  • z_b (double[4], default: 0.0468)

The vertical component of the distance between the momentum block and the center of mass of robot.

  • g (double, default: 9.8)

Gravity constant.

  • i_m (double, default: 0.1982)

The moment of inertia of the robot around the y-axis of base_link coordinate.

  • q (double[16])

Weight matrix.

  • r (double[4])

Weight matrix.

Swerve
  • /modules/<module_name>/position (double[2])

The position of module.

  • /modules/<module_name>/pivot/joint (string)

Joint between chassis and privot.

  • /modules/<module_name>/pivot/offset (double)

Angle between the wheel rotation axis and the chassis's Y axis.

  • /modules/<module_name>/wheel/joint (string)

Joint between privot and wheel.

  • /modules/<module_name>/wheel/radius (double)

The radius of wheel.

Omni
  • /wheels/<wheels_name>/pose (double[3])

The pose of wheel.

  • /wheels/<wheels_name>/joint (string)

wheel joint name.

  • /wheels/left_front/roller_angle (double)

The roller angle of wheel.

  • /wheels/left_front/radius (double)

The radius of wheel.

Controller configuration examples

Complete description

  chassis_controller:
    type: rm_chassis_controllers/OmniController
    publish_rate: 100
    enable_odom_tf: true
    publish_odom_tf: false
    power:
      effort_coeff: 10.0
      vel_coeff: 0.003
      power_offset: -8.41
    twist_angular: 0.5233
    timeout: 0.1
    pid_follow: { p: 5.0, i: 0, d: 0.3, i_max: 0.0, i_min: 0.0, antiwindup: true, publish_state: true }
    twist_covariance_diagonal: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ]

    wheels:
      left_front:
        pose: [ 0.147, 0.147, 2.356 ]
        joint: left_front_wheel_joint
        <<: &wheel_setting
          roller_angle: 0.
          radius: 0.07625
          pid: { p: 0.41, i: 0, d: 0.0, i_max: 0.0, i_min: 0.0, antiwindup: true, publish_state: true }
      right_front:
        pose: [ 0.147, -0.147, 0.785 ]
        joint: right_front_wheel_joint
        <<: *wheel_setting
      left_back:
        pose: [ -0.147, 0.147, -2.356 ]
        joint: left_back_wheel_joint
        <<: *wheel_setting
      right_back:
        pose: [ -0.147, -0.147, -0.785 ]
        joint: right_back_wheel_joint
        <<: *wheel_setting

Bugs & Feature Requests

Please report bugs and request features using the Issue Tracker.

CHANGELOG

Changelog for package rm_chassis_controllers

0.1.11 (2023-06-20)

  • Merge pull request #132 from chenhuiYu00/change_chassis_topic Change chassis command topic.
  • Change chassis command topic.
  • Merge branch \'rm-controls:master\' into master
  • Merge pull request #123 from chenhuiYu00/dev/balance Add balance auto exit block
  • Update balance model value.
  • Rename BalanceMode.
  • Separate balance model into functions.
  • Use realtime pub in balance state.
  • Merge branch \'master\' into dev/balance
  • Merge pull request #120 from ye-luo-xi-tui/master 0.1.10
  • Update GYRO to RAW and enum rename.
  • Merge branch \'master\' into dev/balance
  • Balance auto exit block add pitch limit.
  • Update auto exit block.
  • Add balance auto exit block.
  • Merge branch \'rm-controls:master\' into gpio_calibration_controller
  • Contributors: 1moule, ye-luo-xi-tui, yuchen

0.1.10 (2023-03-25)

  • Merge pull request #112 from ljq-lv/Delete Delete the chassis mode \"GYRO\"
  • Merge pull request #115 from Edwinlinks/fix-odom Add manner to fix odom2base by adding outside odometry.
  • Merge pull request #119 from ye-luo-xi-tui/balance_standard Clear position when position_des minus position_act bigger than threshold
  • Modify topic name and add comment.
  • Delete the unused header.
  • Add manner to fix odom2base by adding outside odometry.
  • Merge branch \'rm-controls:master\' into master
  • Modified the chassis\'s README
  • Delete the chassis mode \"GYRO\"
  • Merge pull request #111 from d0h0s/master Updated README.md of rm_chassis_controllers.
  • Repaired the example of chassis_controller.
  • Added the parameters of Omni and fixed the inappropriate description.
  • Updated README.md of rm_chassis_controllers.
  • Merge pull request #108 from Aung-xiao/master add mecanum.yaml
  • change the name of the controller
  • add mecanum.yaml
  • Merge pull request #106 from ye-luo-xi-tui/master 0.1.9
  • Clear position when position_des minus position_act bigger than threshold.
  • Contributors: Aung-xiao, Edwinlinks, QiayuanLiao, d0h0s, ljq-lv, ye-luo-xi-tui, yezi

0.1.9 (2023-02-21)

  • Merge pull request #105 from ljq-lv/gimbal_toward Add follow gimbal\'s chassis control
  • Add follow gimbal\'s chassis control
  • Add follow gimbal\'s chassis control
  • Merge pull request #100 from ye-luo-xi-tui/balance_standard Add balance chassis controller
  • Update note.
  • Update test.
  • Update controller description.
  • Merge branch \'master\' into balance_standard
  • Modify the expected location update policy.
  • Take some joints\' name as params.
  • Fix warning.
  • Add power limit.
  • Compute state matrix and control matrix with given params.
  • Add balance_chassis\'s odometry.
  • Transform IMU\'s data to base_link.
  • Try to use PID controller to fix the problem that one block\'s position is differ from another.
  • Revised dynamics model and remove gazebo dependency.
  • Merge pull request #97 from ye-luo-xi-tui/master 0.1.8
  • Fix mistake of orientation data.
  • Add some test codes for balance chassis.
  • Contributors: ljq-lv, ye-luo-xi-tui, yezi

0.1.8 (2022-11-24)

  • Merge branch \'master\' into target_velocity_correction
  • Merge pull request #89 from rm-controls/dev Merge branch \'dev\' into master
  • Merge pull request #88 from NaHCO3bc/dev Add a push_back of joint_handles in the new OmniController.
  • Add a push_back of joint_handles in the new OmniController.
  • Merge pull request #86 from NaHCO3bc/Readme Fix the dependence part bug.
  • 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)

  • Merge pull request #83 from rm-controls/dev Merge the new OmniController to master
  • Merge pull request #82 from NaHCO3bc/dev Fix some bugs in the new OmniController.
  • Compute the params and fix some bugs.
  • Rename the function forwardKinematics to odometry.
  • Merge pull request #80 from qiayuanliao/master New and elegant OmniController
  • Fix bug in the new OmniController
  • Add a new and elegant OmniController
  • Merge remote-tracking branch \'origin/master\'
  • Contributors: NaHCO3bc, QiayuanLiao, qiayuan

0.1.6 (2022-06-16)

  • Merge remote-tracking branch \'origin/master\'
  • Contributors: qiayuan

0.1.5 (2022-06-10)

  • Update frames in update function.
  • Add command_source_frame to follow mode.
  • Merge remote-tracking branch \'origin/master\'
  • 0.1.4
  • Add damping behavior to ReactionWheelController
  • Add recover behavior to ReactionWheelController
  • Add a low-pass filter to eliminate the constant pitch angle offset to ReactionWheelController
  • Add a naive method for determining orientation of balance chassis
  • Use new reaction wheel state space model
  • Add setZero to Q and R
  • Merge remote-tracking branch \'origin/master\'
  • Remove \"convert model from continuous to discrete time\" from ReactionWheel, the rm_common::Lqr accept continuous model.
  • Merge pull request #57 from NaHCO3bc/master Update ReactionWheelController
  • Change the number of joint name reads,change the QR matrix to an array and update the rm_chassis_controllers_plugins.xml.
  • Merge branch \'chassis/reaction_wheel\'
  • Merge pull request #56 from NaHCO3bc/chassis/reaction_wheel Update ReactionWheelController
  • Update reaction_wheel.cpp and add template_reaction_wheel.yaml
  • Add some comments of ReactionWheelController
  • Remove BalanceController
  • Add ReactionWheelController
  • Merge pull request #51 from Edwinlinks/sentry_catapult Complete sentry catapult and delete the redundant code
  • Merge branch \'master\' into gimbal_track
  • Complete sentry catapult and delete the redundant code
  • Merge pull request #45 from mlione/master Delete some config files in rm_controllers.
  • Merge pull request #50 from ye-luo-xi-tui/ori Make rm_orientation_controller publish tf use imu data on the topic
  • Delete some config files in rm_controller.
  • Add a param publish_odom_tf, it decided whether tf would be published.
  • Merge pull request #46 from ye-luo-xi-tui/master Deprecated imu_filter_controller
  • Merge branch \'master\' into gimbal_track
  • Contributors: Edwinlinks, QiayuanLiao, YuuinIH, mlione, nahco3bc, qiayuan, yezi

0.1.3 (2022-03-28)

  • Merge branch \'master\' into forward_feed
  • 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 maintain # Conflicts: # rm_chassis_controllers/config/standard3.yaml
  • Merge pull request #41 from ye-luo-xi-tui/standard3 Update standard3 config
  • 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
  • Add missing parameters and format rm_chassis_controllers
  • Update standard3 config
  • Merge remote-tracking branch \'origin/master\'
  • Update standard3 chassis_controller config.
  • Contributors: QiayuanLiao, qiayuan, ye-luo-xi-tui, yezi

0.1.2 (2022-01-08)

  • Merge pull request #31 from ye-luo-xi-tui/modify_params Modify chassis configuration
  • Update standard3.yaml.
  • Update sentry chassis config.
  • Update standard5.yaml
  • Merge pull request #27 from ye-luo-xi-tui/omni_wheel_controller Add omni wheel controller
  • Fix bug in kinematics.
  • Change param name.
  • Merge branch \'master\' into omni_wheel_controller
  • Merge remote-tracking branch \'origin/master\'
  • Merge branch \'rm-controls:master\' into master
  • Merge pull request #24 from ye-luo-xi-tui/fix_power_limit Fix a bug in power limit.
  • Add OmniController.
  • Fix a bug in power limit. (cherry picked from commit 81d1e880ea67aed189cb762819f63d4a5fba6b9b)
  • Merge remote-tracking branch \'origin/master\'
  • Merge branch \'rm-controls:master\' into master
  • Merge branch \'rm-controls:master\' into master
  • Merge pull request #19 from ye-luo-xi-tui/new_power_limit New power limit
  • Add power_offset in new power limit
  • Merge branch \'master\' of https://github.com/YuuinIH/rm_controllers
  • Optimize the code.
  • New power limit
  • Format
  • Use imu_sensor_interface in BalanceController
  • Merge branch \'gimbal/opti_or_simplify\' into chassis/balance_imu_interface
  • Code style
  • Set odom tf in each update of rm_chassis_controllers
  • Merge branch \'master\' into chassis/balance_imu_interface
  • Run pre-commit
  • Modify ChassisBase to template class prepare for adding imu_sensor_interface(only BalanceChassis)
  • Update the config of imu_chassis_controllers, load only one controller on launch instead of spawn controllers
  • Fix pre-commit
  • Correct code format.
  • Correct code format.
  • Correct format.
  • Merge remote-tracking branch \'origin/chassis/fix_filter\' into chassis/fix_filter # Conflicts: # rm_chassis_controllers/src/chassis_base.cpp # rm_chassis_controllers/src/swerve.cpp
  • Filter the linear vel before transform and filter the angular vel after PID.
  • Delete if (std::abs(vel_cmd_.x) + std::abs(vel_cmd_.y) >= 0.01)
  • Merge branch \'master\' into chassis/fix_filter
  • Delet #endif
  • Merge remote-tracking branch \'origin/master\'
  • Filter the linear vel before transform and filter the angular vel after PID.
  • Set transform on buffer when publishing odom tf.
  • Update static_transform_publisher from tf to tf2
  • 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
  • Merge pull request #10 from ye-luo-xi-tui/master Update README of chassis controller
  • Change name of namespace:from hardware_interface to rm_control.
  • Update README.md of rm_chassis_controllers
  • Fix format error
  • Add doxygen on sentry.h
  • Add doxygen on chassis_base.h
  • Add doxygen on mecanum.h
  • Add doxygen on balance.h
  • Add nav_msgs to rm_chassis_controllers
  • update README of chassis controller
  • update README of chassis controller
  • Update README.md
  • Merge pull request #9 from ye-luo-xi-tui/master update README.md of chassis controller
  • README.md
  • Code style
  • Use "pragma once" in rm_chassis_controllers headers instead of include guards.
  • Update shooter param\'s description.
  • Correct readme format.
  • Correct readme format.
  • Correct readme format.
  • Update controllers README.
  • Update controllers README.
  • Run pre-commit
  • Format rm_chassis_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
  • Remove test_depend of rm_chassis_controllers
  • Merge remote-tracking branch \'alias_memory/metapackage\'
  • Move all files to rm_chassis_controllers/rm_chassis_controllers, prepare for merge
  • Contributors: qiayuan

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Launch files

Messages

No message files found.

Services

No service files found

Recent questions tagged rm_chassis_controllers at Robotics Stack Exchange