-
 
No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

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

RoboMaster standard robot Gimbal controller

Additional Links

No additional links.

Maintainers

  • Qiayuan Liao

Authors

  • Qiayuan Liao

rm_calibration_controllers

Overview

Since the zero point of some motors will change after power off, rm_calibration_controllers will move after it is started until motors reach the position we wanted,and motors position will be reset to zero,which can come true by two ways.One is that mechanical_calibration_controller stops moving after it reaches the mechanical limit.Another one is that gpio_calibration_controller moves at a fast speed until gpio changes to be different from initial gpio.Then it will retreat at a small angle and restore initial gpio.Finally it moves at a slow speed until the state of gpio changes to be different from initial gpio again.

Keywords: calibration, ROS, position.

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

  • EffortJointInterface Used to send effort command to target joint to make it reach the calibration speed.
  • ActuatorExtraInterface Used to obtain the information of the target actuators offset, current position, the state of the whether it is stopped and the state of whether it is calibrated.
  • GpioStateInterface Used to obtain the state of gpio.

Installation

Installation from Packages

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

sudo apt-get install ros-noetic-calibration-controllers

Or better, use rosdep:

sudo rosdep install --from-paths src

Dependencies

  • roscpp
  • rm_common
  • effort_controllers
  • controller_interface

ROS API

Service

Parameters

calibration_base

  • search_velocity (double)

    The joint velocity of calibrating.

mechanical_calibration_controller

  • velocity_threshold_ (double)

    This is velocity threshold. When the real time velocity of target joint lower than threshold, and last for a while, it can switch CALIBRATED from MOVING.

gpio_calibration_controller

  • backward_angle (double)

    The angle of retreat when gpio changes to be different form initial gpio for the first time.

  • slow_forward_velocity (double)

    The velocity of second forward movement for reaching a more accurate calibration-position.

  • pos_threshold (double)

    The threshold for the difference between the command position and the current position.

Complete description

mechanical_calibration_controller

trigger_calibration_controller:
  type: rm_calibration_controllers/MechanicalCalibrationController
  actuator: [ trigger_joint_motor ]
  velocity:
    search_velocity: 4.0
    vel_threshold: 0.001
    joint: trigger_joint
    pid: { p: 0.8, i: 0, d: 0.0, i_clamp_max: 0.0, i_clamp_min: 0.0, antiwindup: true }

gpio_calibration_controller

yaw_calibration_controller:
  type: rm_calibration_controllers/GpioCalibrationController
  actuator: [ yaw_joint_motor ]
  gpio: "yaw"
  initial_gpio_state: false
  velocity:
    search_velocity: -4.0
    slow_forward_velocity: -2.0
    joint: yaw_joint
    pid: { p: 0.19, i: 0, d: 0.0, i_clamp_max: 0.0, i_clamp_min: 0.0, antiwindup: true }
  position:
    pos_threshold: 0.01
    backward_angle: -0.15
    joint: yaw_joint
    pid: { p: 7.0, i: 0, d: 0.0, i_clamp_max: 0.0, i_clamp_min: 0.0, antiwindup: true }

Bugs & Feature Requests

Please report bugs and request features using the Issue Tracker.

CHANGELOG

Changelog for package rm_calibration_controllers

0.1.11 (2023-06-20)

  • Merge pull request #127 from 1moule/gpio_calibration_controller Rewrite the stopping function and set calibration success to false in stopping function
  • Rewrite the stopping function and set calibration success to false in the stopping function.
  • Merge pull request #126 from 1moule/master Remove unnecessary variables
  • Remove unnecessary variables.
  • Merge pull request #125 from rm-controls/calibration Add gpio calibration controller
  • Merge pull request #116 from 1moule/gpio_calibration_controller Split the calibration controller and add a controller that uses gpio calibration
  • Modefy CMakeLists, delete TODO and initialize a variable.
  • Modified to get the error message when gpio is obtained.
  • Delete vector and some unnecessary code.
  • Merge branch 'master' into dev/balance
  • Change gpio calibration controller to the same one and modify gpio calibration logic.
  • Merge pull request #120 from ye-luo-xi-tui/master 0.1.10
  • Modify the unmodified name in the joint calibration controller.
  • Rename joint calibration controller.
  • Write the velocity threshold in the base class.
  • Modify the name of an enumeration type.
  • Modify the name of an enumeration type.
  • Modify variable name.
  • Delete some comments, modify the initialization function of the gpio calibration controller base class.
  • Modified hardware interface for instantiating template classes.
  • Add a new line at the end and delete update function of calibration_base.h file.
  • Factor out the calibration controller into a form derived from a base class and modify the controller appropriately.
  • Use gpio handle to replace gpio call back function.
  • Solved the problem of not being in the detection range of the hall switch when starting the calibration.
  • Modify gpio calibration controller scheme to first use speed control to find a fixed point, and then use position control to reach.
  • Modify logic and callback function of gpio calibration controller.
  • Modify queue length of gpio subscriber.
  • Merge branch 'rm-controls:master' into gpio_calibration_controller
  • Add gpio calibration controller.
  • Contributors: 1moule, ye-luo-xi-tui, yuchen

0.1.10 (2023-03-25)

  • Merge pull request #106 from ye-luo-xi-tui/master 0.1.9
  • Contributors: ye-luo-xi-tui

0.1.9 (2023-02-21)

  • Merge pull request #103 from L-SY/fix_return Fix calibration controller no return true.
  • Fix bug.
  • Run pre-commit.
  • Merge branch 'master' into balance_standard
  • Add engineer trigger ui .
  • Merge pull request #96 from L-SY/fix_return Fix joint_calibration_controller
  • Delete repetitive set.
  • delete useless target_velocity_.
  • Merge pull request #97 from ye-luo-xi-tui/master 0.1.8
  • eyes is lost.
  • Update fix can not return .
  • Contributors: lsy, ye-luo-xi-tui, yezi

0.1.8 (2022-11-24)

  • Merge branch 'master' into target_velocity_correction
  • Merge pull request #87 from NaHCO3bc/Readme Fix the dependence bug in rm_calibration_controllers.
  • Fix the dependence bug in rm_calibration_controllers.
  • 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 remote-tracking branch 'origin/master'
  • Contributors: qiayuan

0.1.6 (2022-06-16)

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

0.1.5 (2022-06-10)

  • Merge remote-tracking branch 'origin/master'
  • 0.1.4
  • 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
  • Contributors: QiayuanLiao, YuuinIH, mlione, qiayuan, yezi

0.1.3 (2022-03-28)

  • Merge branch 'master' into forward_feed
  • Merge branch 'master' into standard3
  • Merge remote-tracking branch 'origin/master'
  • Contributors: qiayuan, ye-luo-xi-tui, yezi

0.1.2 (2022-01-08)

  • Merge branch 'master' into chassis/fix_filter
  • Merge remote-tracking branch 'origin/master'
  • 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
  • Change name of namespace:from hardware_interface to rm_control.
  • Merge pull request #7 from kbxkgxjg/patch-1 Add white line behind title on calibration_controller README.md
  • Add white line behind title
  • Rename motor to actuators
  • Merge pull request #6 from kbxkgxjg/master Add doxygen comments on joint_calibration_controller.h
  • Modify the meaning of [param req]{.title-ref}
  • Fix clang-format error
  • Modify the params
  • Update the comments of is calibrated()
  • Update the comments of starting()
  • Update the comments of update()
  • Update the comments of init()
  • Modify 'current joint state' to 'current calibration joint state'
  • Modift '' to '@'
  • Modify "actuator state" to "joint state " and Modify motors to actuators
  • Modify format
  • Delete white line
  • Delete a whitespace
  • Add annotation to function
  • Use “pragma once” in rm_calibration_controllers headers instead of include guards.
  • Merge pull request #2 from kbxkgxjg/master Update README.md on rm_calibration_controllers
  • Modify the meaning of [search_velocity]{.title-ref} and [threshold]{.title-ref}
  • Revert "Modify 'is_calibrated_srv' to 'is_calibrated'" This reverts commit b5b06dfe
  • Delete a net
  • Modify 'is_calibrated_srv' to 'is_calibrated'
  • Add angular in front of velocity
  • fixed grammar error
  • Modify the meaning of [is_calibrated_srv_]{.title-ref}
  • Modify a wrong hardware interface name
  • Add "Hardware interface type", modify "License" and Delete number
  • Modify actuator to motor
  • Add a white line in front of “Or better”
  • Delete 啊
  • Delete a white line
  • Modify the font in Installation
  • Modify overview
  • Update the format of Installation
  • Add . behind CLIBRATIED
  • Modify the meaning of [search_velocity]{.title-ref} [threshold]{.title-ref}
  • Delete a white line
  • Add tap before begin and modify Installation from Packages
  • Delete whitespace before 'When .…'
  • Explain the 'search_velocity' 'threshold' together
  • Modify services to service
  • Modify format and modify the explanation of [is_calibrated_srv_]{.title-ref}
  • Delete a whitespace between parameters and data type
  • Modify the font size in ROS API, and delete ' . ' behind 3 .1 3.2
  • Add a whitespace between parameter and date type
  • Add ' ' to double
  • Modify Installation from Packages
  • Modify date type of 'is_calibrated_srv_'
  • Update 'Installation from Packages'
  • Update the explanation of 'is_calibrated_srv_'
  • Delete a whitespace
  • Delete '*' and change number
  • Delete a whitespace
  • Delete usage, and change the data type of [is_calibrated_srv_]{.title-ref}
  • Delete config and pid
  • Add the type of the data And delete 'type' 'joint' 'actuators' parameters
  • Add rm_calibration_controllers README.md
  • Update README.md Add a line
  • Delete a whitespace
  • Add README.md
  • Fix wrong naming "include/rm_gimbal_controller"
  • Run pre-commit
  • Contributors: BruceLannn, QiayuanLiao, chenzheng, kbxkgxjg, ljq, qiayuan, yezi, 吕骏骐

0.1.1 (2021-08-12)

  • Set all version to the same
  • Add license to rm_calibration_controllers source files
  • Merge remote-tracking branch 'alias_memory/metapackage'
  • Move all files to rm_calibration_controllers/rm_calibration_controllers, prepare for merge
  • Contributors: qiayuan

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Package Dependencies

System Dependencies

No direct system dependencies.

Dependant Packages

Name Deps
rm_controllers

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Recent questions tagged rm_calibration_controllers at Robotics Stack Exchange

No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.