gpio_calibration_controller.h
Go to the documentation of this file.
1 //
2 // Created by guanlin on 22-11-7.
3 //
4 
5 #pragma once
6 
9 
11 {
13  : public CalibrationBase<rm_control::ActuatorExtraInterface, rm_control::GpioStateInterface,
14  hardware_interface::EffortJointInterface>
15 {
16 public:
17  GpioCalibrationController() = default;
18  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
19  void update(const ros::Time& time, const ros::Duration& period) override;
20 
21 private:
22  enum State
23  {
27  };
31 };
32 } // namespace rm_calibration_controllers
rm_calibration_controllers::GpioCalibrationController
Definition: gpio_calibration_controller.h:12
rm_calibration_controllers::GpioCalibrationController::position_threshold_
double position_threshold_
Definition: gpio_calibration_controller.h:28
rm_calibration_controllers::GpioCalibrationController::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: gpio_calibration_controller.cpp:46
rm_calibration_controllers::GpioCalibrationController::slow_forward_velocity_
double slow_forward_velocity_
Definition: gpio_calibration_controller.h:28
rm_calibration_controllers::GpioCalibrationController::backward_angle_
double backward_angle_
Definition: gpio_calibration_controller.h:28
rm_calibration_controllers::GpioCalibrationController::start_retreat_position_
double start_retreat_position_
Definition: gpio_calibration_controller.h:28
rm_calibration_controllers::GpioCalibrationController::SLOW_FORWARD
@ SLOW_FORWARD
Definition: gpio_calibration_controller.h:26
rm_calibration_controllers::GpioCalibrationController::RETREAT
@ RETREAT
Definition: gpio_calibration_controller.h:25
hardware_interface::RobotHW
rm_calibration_controllers::GpioCalibrationController::initial_gpio_state_
bool initial_gpio_state_
Definition: gpio_calibration_controller.h:30
rm_calibration_controllers::GpioCalibrationController::gpio_state_handle_
rm_control::GpioStateHandle gpio_state_handle_
Definition: gpio_calibration_controller.h:29
rm_calibration_controllers
Definition: calibration_base.h:17
rm_calibration_controllers::GpioCalibrationController::State
State
Definition: gpio_calibration_controller.h:22
joint_position_controller.h
ros::Time
rm_calibration_controllers::GpioCalibrationController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: gpio_calibration_controller.cpp:10
rm_calibration_controllers::GpioCalibrationController::FAST_FORWARD
@ FAST_FORWARD
Definition: gpio_calibration_controller.h:24
rm_control::GpioStateHandle
rm_calibration_controllers::CalibrationBase
Definition: calibration_base.h:20
calibration_base.h
rm_calibration_controllers::GpioCalibrationController::GpioCalibrationController
GpioCalibrationController()=default
ros::Duration
ros::NodeHandle


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