differential_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 cch on 24-8-7.
36 //
37 
39 
41 
43 {
45  ros::NodeHandle& controller_nh)
46 {
47  CalibrationBase::init(robot_hw, root_nh, controller_nh);
48  XmlRpc::XmlRpcValue actuator;
49  ros::NodeHandle nh2(controller_nh, "joint2");
51  if (!controller_nh.getParam("max_calibretion_time", max_calibretion_time_))
52  {
54  ROS_ERROR("No given max calibration time, set to default (5s).");
55  }
56  if (!controller_nh.getParam("actuator", actuator))
57  {
58  ROS_ERROR("No actuator given (namespace: %s)", controller_nh.getNamespace().c_str());
59  return false;
60  }
61  actuator2_ = robot_hw->get<rm_control::ActuatorExtraInterface>()->getHandle(actuator[1]);
62  if (!controller_nh.getParam("velocity/vel_threshold", velocity_threshold_))
63  {
64  ROS_ERROR("Velocity threshold was not specified (namespace: %s)", controller_nh.getNamespace().c_str());
65  return false;
66  }
67  if (velocity_threshold_ < 0)
68  {
69  velocity_threshold_ *= -1.;
70  ROS_ERROR("Negative velocity threshold is not supported for joint %s. Making the velocity threshold positive.",
71  velocity_ctrl_.getJointName().c_str());
72  }
73  calibration_success_ = false;
74  return true;
75 }
76 
78 {
79  switch (state_)
80  {
81  case INITIALIZED:
82  {
86  countdown_ = 100;
88  break;
89  }
90  case MOVING_POSITIVE:
91  {
93  countdown_--;
94  else
95  countdown_ = 100;
97  {
101  actuator_.setCalibrated(true);
104  << " are calibrated.");
105  state_ = CALIBRATED;
109  calibration_success_ = true;
110  }
111  velocity_ctrl_.update(time, period);
112  position_ctrl2_.update(time, period);
113  break;
114  }
115  case CALIBRATED:
116  {
117  velocity_ctrl_.update(time, period);
118  position_ctrl2_.update(time, period);
119  break;
120  }
121  }
122 }
123 } // namespace rm_calibration_controllers
124 
rm_calibration_controllers::DifferentialCalibrationController
Definition: differential_calibration_controller.h:76
rm_calibration_controllers::DifferentialCalibrationController::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: differential_calibration_controller.cpp:108
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
rm_calibration_controllers::DifferentialCalibrationController::MOVING_POSITIVE
@ MOVING_POSITIVE
Definition: differential_calibration_controller.h:118
effort_controllers::JointPositionController::init
bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
effort_controllers::JointVelocityController::getJointName
std::string getJointName()
getHandle
ROSCONSOLE_CONSOLE_IMPL_DECL void * getHandle(const std::string &name)
hardware_interface::JointHandle::setCommand
void setCommand(double command)
rm_calibration_controllers::DifferentialCalibrationController::position_ctrl2_
effort_controllers::JointPositionController position_ctrl2_
Definition: differential_calibration_controller.h:127
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)
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
controller_interface::ControllerBase
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::state_
int state_
Definition: calibration_base.h:63
hardware_interface::RobotHW
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
hardware_interface::EffortJointInterface
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::calibration_success_
bool calibration_success_
Definition: calibration_base.h:65
effort_controllers::JointPositionController::joint_
hardware_interface::JointHandle joint_
effort_controllers::JointVelocityController::setCommand
void setCommand(double cmd)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
rm_calibration_controllers
Definition: calibration_base.h:17
rm_control::ActuatorExtraInterface
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
effort_controllers::JointPositionController::getJointName
std::string getJointName()
hardware_interface::JointStateHandle::getVelocity
double getVelocity() const
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
differential_calibration_controller.h
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
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
rm_calibration_controllers::DifferentialCalibrationController::max_calibretion_time_
double max_calibretion_time_
Definition: differential_calibration_controller.h:123
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
rm_control::ActuatorExtraHandle::setCalibrated
void setCalibrated(bool calibrated)
rm_control::ActuatorExtraHandle::getPosition
double getPosition() const
ros::Duration
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >::velocity_ctrl_
effort_controllers::JointVelocityController velocity_ctrl_
Definition: calibration_base.h:67
effort_controllers::JointPositionController::getPosition
double getPosition()
XmlRpc::XmlRpcValue
effort_controllers::JointVelocityController::joint_
hardware_interface::JointHandle joint_
ros::NodeHandle
ros::Time::now
static Time now()


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