mechanical_calibration_controller.cpp
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 
39 
41 
43 {
45  ros::NodeHandle& controller_nh)
46 {
47  CalibrationBase::init(robot_hw, root_nh, controller_nh);
48  is_return_ = is_center_ = false;
49  controller_nh.getParam("center", is_center_);
50  if (!controller_nh.getParam("velocity/vel_threshold", velocity_threshold_))
51  {
52  ROS_ERROR("Velocity threshold was not specified (namespace: %s)", controller_nh.getNamespace().c_str());
53  return false;
54  }
55  if (velocity_threshold_ < 0)
56  {
57  velocity_threshold_ *= -1.;
58  ROS_ERROR("Negative velocity threshold is not supported for joint %s. Making the velocity threshold positive.",
59  velocity_ctrl_.getJointName().c_str());
60  }
61  if (controller_nh.hasParam("return"))
62  {
63  ros::NodeHandle nh_return(controller_nh, "return");
65  if (!nh_return.getParam("target_position", target_position_))
66  {
67  ROS_ERROR("Position value was not specified (namespace: %s)", nh_return.getNamespace().c_str());
68  return false;
69  }
70  if (!nh_return.getParam("pos_threshold", position_threshold_))
71  {
72  ROS_ERROR("Position value was not specified (namespace: %s)", nh_return.getNamespace().c_str());
73  return false;
74  }
75  is_return_ = true;
76  calibration_success_ = false;
77  }
78  return true;
79 }
80 
82 {
83  switch (state_)
84  {
85  case INITIALIZED:
86  {
88  countdown_ = 100;
90  break;
91  }
92  case MOVING_POSITIVE:
93  {
95  countdown_--;
96  else
97  countdown_ = 100;
98  if (countdown_ < 0)
99  {
101  if (!is_center_)
102  {
104  actuator_.setCalibrated(true);
105  ROS_INFO("Joint %s calibrated", velocity_ctrl_.getJointName().c_str());
106  state_ = CALIBRATED;
107  if (is_return_)
108  {
110  }
111  else
112  {
114  calibration_success_ = true;
115  }
116  }
117  else
118  {
120  countdown_ = 100;
123  }
124  }
125  velocity_ctrl_.update(time, period);
126  break;
127  }
128  case MOVING_NEGATIVE:
129  {
131  countdown_--;
132  else
133  countdown_ = 100;
134  if (countdown_ < 0)
135  {
139  actuator_.setCalibrated(true);
140  ROS_INFO("Joint %s calibrated", velocity_ctrl_.getJointName().c_str());
141  state_ = CALIBRATED;
142  if (is_return_)
144  else
145  {
147  calibration_success_ = true;
148  }
149  }
150  velocity_ctrl_.update(time, period);
151  break;
152  }
153  case CALIBRATED:
154  {
155  if (is_return_)
156  {
158  calibration_success_ = true;
159  position_ctrl_.update(time, period);
160  }
161  else
162  velocity_ctrl_.update(time, period);
163  break;
164  }
165  }
166 }
167 } // namespace rm_calibration_controllers
168 
mechanical_calibration_controller.h
rm_calibration_controllers::MechanicalCalibrationController
Definition: mechanical_calibration_controller.h:76
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::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::position_ctrl_
effort_controllers::JointPositionController position_ctrl_
Definition: calibration_base.h:68
effort_controllers::JointVelocityController::update
void update(const ros::Time &time, const ros::Duration &period)
hardware_interface::InterfaceManager::get
T * get()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
effort_controllers::JointPositionController::init
bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
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
effort_controllers::JointVelocityController::getJointName
std::string getJointName()
rm_control::ActuatorExtraHandle::getHalted
bool getHalted() const
hardware_interface::JointHandle::setCommand
void setCommand(double command)
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::velocity_search_
double velocity_search_
Definition: calibration_base.h:64
rm_control::ActuatorExtraHandle::setOffset
void setOffset(double offset)
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rm_calibration_controllers::MechanicalCalibrationController::MOVING_NEGATIVE
@ MOVING_NEGATIVE
Definition: mechanical_calibration_controller.h:141
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::state_
int state_
Definition: calibration_base.h:63
hardware_interface::RobotHW
rm_calibration_controllers::MechanicalCalibrationController::positive_position_
double positive_position_
Definition: mechanical_calibration_controller.h:145
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::INITIALIZED
@ INITIALIZED
Definition: calibration_base.h:60
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::actuator_
rm_control::ActuatorExtraHandle actuator_
Definition: calibration_base.h:66
effort_controllers::JointPositionController::update
void update(const ros::Time &time, const ros::Duration &period)
rm_control::ActuatorExtraHandle::getOffset
double getOffset() const
rm_calibration_controllers::CalibrationBase::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: calibration_base.cpp:14
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
hardware_interface::EffortJointInterface
rm_calibration_controllers::MechanicalCalibrationController::negative_position_
double negative_position_
Definition: mechanical_calibration_controller.h:145
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::calibration_success_
bool calibration_success_
Definition: calibration_base.h:65
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
effort_controllers::JointPositionController::joint_
hardware_interface::JointHandle joint_
effort_controllers::JointVelocityController::setCommand
void setCommand(double cmd)
rm_calibration_controllers
Definition: calibration_base.h:17
effort_controllers::JointPositionController::setCommand
void setCommand(double pos_target)
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::CALIBRATED
@ CALIBRATED
Definition: calibration_base.h:61
hardware_interface::JointStateHandle::getVelocity
double getVelocity() const
ros::Time
hardware_interface::JointStateHandle::getPosition
double getPosition() const
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
rm_calibration_controllers::MechanicalCalibrationController::velocity_threshold_
double velocity_threshold_
Definition: mechanical_calibration_controller.h:144
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
rm_control::ActuatorExtraHandle::setCalibrated
void setCalibrated(bool calibrated)
ROS_INFO
#define ROS_INFO(...)
rm_calibration_controllers::MechanicalCalibrationController::position_threshold_
double position_threshold_
Definition: mechanical_calibration_controller.h:144
rm_control::ActuatorExtraHandle::getPosition
double getPosition() const
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::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::velocity_ctrl_
effort_controllers::JointVelocityController velocity_ctrl_
Definition: calibration_base.h:67
rm_calibration_controllers::MechanicalCalibrationController::target_position_
double target_position_
Definition: mechanical_calibration_controller.h:145
effort_controllers::JointVelocityController::joint_
hardware_interface::JointHandle joint_
ros::NodeHandle


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