calibration_base.h
Go to the documentation of this file.
1 //
2 // Created by guanlin on 23-3-14.
3 //
4 
5 #pragma once
6 
7 #include <ros/ros.h>
15 #include <control_msgs/QueryCalibrationState.h>
16 
18 {
19 template <typename... T>
21 {
22 public:
23  CalibrationBase() = default;
36  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
43  void starting(const ros::Time& time) override;
44  void stopping(const ros::Time& time) override;
45 
46 protected:
55  bool isCalibrated(control_msgs::QueryCalibrationState::Request& req,
56  control_msgs::QueryCalibrationState::Response& resp);
58  enum State
59  {
62  };
63  int state_{};
64  double velocity_search_{};
65  bool calibration_success_ = false;
69 };
70 
71 } // namespace rm_calibration_controllers
rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, rm_control::GpioStateInterface, hardware_interface::EffortJointInterface >::State
State
Definition: calibration_base.h:58
rm_calibration_controllers::CalibrationBase::position_ctrl_
effort_controllers::JointPositionController position_ctrl_
Definition: calibration_base.h:68
ros.h
joint_velocity_controller.h
rm_calibration_controllers::CalibrationBase::isCalibrated
bool isCalibrated(control_msgs::QueryCalibrationState::Request &req, control_msgs::QueryCalibrationState::Response &resp)
Provide a service to know the state of target actuators.
Definition: calibration_base.cpp:53
rm_calibration_controllers::CalibrationBase::velocity_search_
double velocity_search_
Definition: calibration_base.h:64
ros::ServiceServer
effort_controllers::JointVelocityController
actuator_extra_interface.h
joint_command_interface.h
rm_calibration_controllers::CalibrationBase::state_
int state_
Definition: calibration_base.h:63
hardware_interface::RobotHW
rm_calibration_controllers::CalibrationBase::starting
void starting(const ros::Time &time) override
Switch all of the actuators state to INITIALIZED.
Definition: calibration_base.cpp:37
controller_interface::MultiInterfaceController
rm_calibration_controllers::CalibrationBase::INITIALIZED
@ INITIALIZED
Definition: calibration_base.h:60
rm_calibration_controllers::CalibrationBase::stopping
void stopping(const ros::Time &time) override
Definition: calibration_base.cpp:47
rm_calibration_controllers::CalibrationBase::actuator_
rm_control::ActuatorExtraHandle actuator_
Definition: calibration_base.h:66
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::CalibrationBase::calibration_success_
bool calibration_success_
Definition: calibration_base.h:65
rm_calibration_controllers::CalibrationBase::CalibrationBase
CalibrationBase()=default
rm_calibration_controllers
Definition: calibration_base.h:17
rm_calibration_controllers::CalibrationBase::CALIBRATED
@ CALIBRATED
Definition: calibration_base.h:61
joint_position_controller.h
robot_state_interface.h
effort_controllers::JointPositionController
ros::Time
rm_calibration_controllers::CalibrationBase
Definition: calibration_base.h:20
rm_calibration_controllers::CalibrationBase::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition: calibration_base.h:57
rm_calibration_controllers::CalibrationBase::velocity_ctrl_
effort_controllers::JointVelocityController velocity_ctrl_
Definition: calibration_base.h:67
rm_control::ActuatorExtraHandle
ros::NodeHandle
gpio_interface.h
multi_interface_controller.h


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