differential_calibration_controller.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 cch on 24-8-7.
36 //
37 
38 #pragma once
42 
44 {
45 class DifferentialCalibrationController
46  : public CalibrationBase<rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface>
47 {
48 public:
50  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
51  void update(const ros::Time& time, const ros::Duration& period) override;
52 
53 private:
54  enum State
55  {
56  MOVING_POSITIVE = 3,
58  };
60  int countdown_{};
66 };
67 } // namespace rm_calibration_controllers
rm_calibration_controllers::DifferentialCalibrationController::MOVING_NEGATIVE
@ MOVING_NEGATIVE
Definition: differential_calibration_controller.h:119
rm_calibration_controllers::DifferentialCalibrationController::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: differential_calibration_controller.cpp:108
rm_calibration_controllers::DifferentialCalibrationController::State
State
Definition: differential_calibration_controller.h:116
joint_effort_controller.h
rm_calibration_controllers::DifferentialCalibrationController::MOVING_POSITIVE
@ MOVING_POSITIVE
Definition: differential_calibration_controller.h:118
forward_command_controller::ForwardCommandController< hardware_interface::EffortJointInterface >
rm_calibration_controllers::DifferentialCalibrationController::position_ctrl2_
effort_controllers::JointPositionController position_ctrl2_
Definition: differential_calibration_controller.h:127
rm_calibration_controllers::DifferentialCalibrationController::actuator2_
rm_control::ActuatorExtraHandle actuator2_
Definition: differential_calibration_controller.h:124
rm_calibration_controllers::DifferentialCalibrationController::start_time_
ros::Time start_time_
Definition: differential_calibration_controller.h:121
effort_controllers::JointVelocityController
rm_calibration_controllers::DifferentialCalibrationController::DifferentialCalibrationController
DifferentialCalibrationController()=default
hardware_interface::RobotHW
rm_calibration_controllers
Definition: calibration_base.h:17
rm_calibration_controllers::DifferentialCalibrationController::velocity_ctrl2_
effort_controllers::JointVelocityController velocity_ctrl2_
Definition: differential_calibration_controller.h:125
joint_position_controller.h
rm_calibration_controllers::DifferentialCalibrationController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: differential_calibration_controller.cpp:75
effort_controllers::JointPositionController
ros::Time
rm_calibration_controllers::DifferentialCalibrationController::velocity_threshold_
double velocity_threshold_
Definition: differential_calibration_controller.h:123
rm_calibration_controllers::DifferentialCalibrationController::countdown_
int countdown_
Definition: differential_calibration_controller.h:122
rm_calibration_controllers::DifferentialCalibrationController::max_calibretion_time_
double max_calibretion_time_
Definition: differential_calibration_controller.h:123
calibration_base.h
ros::Duration
rm_control::ActuatorExtraHandle
rm_calibration_controllers::DifferentialCalibrationController::effort_ctrl_
effort_controllers::JointEffortController effort_ctrl_
Definition: differential_calibration_controller.h:126
ros::NodeHandle
rm_calibration_controllers::DifferentialCalibrationController::position_threshold_
double position_threshold_
Definition: differential_calibration_controller.h:123


rm_calibration_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:14