mechanical_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 qiayuan on 5/16/21.
36 //
37 
38 #pragma once
39 
42 
44 {
45 class MechanicalCalibrationController
46  : public CalibrationBase<rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface>
47 {
48 public:
62  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
73  void update(const ros::Time& time, const ros::Duration& period) override;
74 
75 private:
76  enum State
77  {
78  MOVING_POSITIVE = 3,
80  };
81  int countdown_{};
84  bool is_return_{}, is_center_{};
85 };
86 
87 } // namespace rm_calibration_controllers
rm_calibration_controllers::MechanicalCalibrationController::State
State
Definition: mechanical_calibration_controller.h:138
rm_calibration_controllers::MechanicalCalibrationController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Get necessary params from param server. Init joint_calibration_controller.
Definition: mechanical_calibration_controller.cpp:75
rm_calibration_controllers::MechanicalCalibrationController::update
void update(const ros::Time &time, const ros::Duration &period) override
Execute corresponding action according to current calibration controller state.
Definition: mechanical_calibration_controller.cpp:112
rm_calibration_controllers::MechanicalCalibrationController::MechanicalCalibrationController
MechanicalCalibrationController()=default
rm_calibration_controllers::MechanicalCalibrationController::MOVING_NEGATIVE
@ MOVING_NEGATIVE
Definition: mechanical_calibration_controller.h:141
hardware_interface::RobotHW
rm_calibration_controllers::MechanicalCalibrationController::positive_position_
double positive_position_
Definition: mechanical_calibration_controller.h:145
rm_calibration_controllers::MechanicalCalibrationController::countdown_
int countdown_
Definition: mechanical_calibration_controller.h:143
rm_calibration_controllers::MechanicalCalibrationController::MOVING_POSITIVE
@ MOVING_POSITIVE
Definition: mechanical_calibration_controller.h:140
rm_calibration_controllers::MechanicalCalibrationController::negative_position_
double negative_position_
Definition: mechanical_calibration_controller.h:145
rm_calibration_controllers
Definition: calibration_base.h:17
joint_position_controller.h
ros::Time
calibration_base.h
rm_calibration_controllers::MechanicalCalibrationController::velocity_threshold_
double velocity_threshold_
Definition: mechanical_calibration_controller.h:144
rm_calibration_controllers::MechanicalCalibrationController::position_threshold_
double position_threshold_
Definition: mechanical_calibration_controller.h:144
rm_calibration_controllers::MechanicalCalibrationController::is_center_
bool is_center_
Definition: mechanical_calibration_controller.h:146
ros::Duration
rm_calibration_controllers::MechanicalCalibrationController::is_return_
bool is_return_
Definition: mechanical_calibration_controller.h:146
rm_calibration_controllers::MechanicalCalibrationController::target_position_
double target_position_
Definition: mechanical_calibration_controller.h:145
ros::NodeHandle


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