Public Member Functions | Private Types | Private Attributes | List of all members
rm_calibration_controllers::MechanicalCalibrationController Class Reference

#include <mechanical_calibration_controller.h>

Inheritance diagram for rm_calibration_controllers::MechanicalCalibrationController:
Inheritance graph
[legend]

Public Member Functions

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. More...
 
 MechanicalCalibrationController ()=default
 
void update (const ros::Time &time, const ros::Duration &period) override
 Execute corresponding action according to current calibration controller state. More...
 
- Public Member Functions inherited from rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >
 CalibrationBase ()=default
 
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. More...
 
void starting (const ros::Time &time) override
 Switch all of the actuators state to INITIALIZED. More...
 
void stopping (const ros::Time &time) override
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< T... >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Private Types

enum  State { MOVING_POSITIVE = 3, MOVING_NEGATIVE }
 

Private Attributes

int countdown_ {}
 
bool is_center_ {}
 
bool is_return_ {}
 
double negative_position_ {}
 
double position_threshold_ {}
 
double positive_position_ {}
 
double target_position_ {}
 
double velocity_threshold_ {}
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 
- Protected Types inherited from rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >
enum  State
 
- Protected Member Functions inherited from rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >
bool isCalibrated (control_msgs::QueryCalibrationState::Request &req, control_msgs::QueryCalibrationState::Response &resp)
 Provide a service to know the state of target actuators. More...
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< T... >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< T... >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 
- Protected Attributes inherited from rm_calibration_controllers::CalibrationBase< rm_control::ActuatorExtraInterface, hardware_interface::EffortJointInterface >
rm_control::ActuatorExtraHandle actuator_
 
bool calibration_success_
 
ros::ServiceServer is_calibrated_srv_
 
effort_controllers::JointPositionController position_ctrl_
 
int state_
 
effort_controllers::JointVelocityController velocity_ctrl_
 
double velocity_search_
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< T... >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

Detailed Description

Definition at line 76 of file mechanical_calibration_controller.h.

Member Enumeration Documentation

◆ State

Enumerator
MOVING_POSITIVE 
MOVING_NEGATIVE 

Definition at line 138 of file mechanical_calibration_controller.h.

Constructor & Destructor Documentation

◆ MechanicalCalibrationController()

rm_calibration_controllers::MechanicalCalibrationController::MechanicalCalibrationController ( )
default

Member Function Documentation

◆ init()

bool rm_calibration_controllers::MechanicalCalibrationController::init ( hardware_interface::RobotHW robot_hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

Get necessary params from param server. Init joint_calibration_controller.

Get params from param server and check whether these params are set.Init JointVelocityController.Check whether threshold is set correctly.

Parameters
robot_hwThe robot hardware abstraction.
root_nhA NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services).
controller_nhA NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides.
Returns
True if init successful, false when failed.

Reimplemented from controller_interface::MultiInterfaceController< T... >.

Definition at line 75 of file mechanical_calibration_controller.cpp.

◆ update()

void rm_calibration_controllers::MechanicalCalibrationController::update ( const ros::Time time,
const ros::Duration period 
)
overridevirtual

Execute corresponding action according to current calibration controller state.

Execute corresponding action according to current joint state. If INITIALIZED, target joint will be set a vel_search_ and countdown_ to move, and switch state to MOVING. If MOVING, target joint will move until current velocity lower than threshold last for a while, and switch state to CALIBRATED. If CALIBRATED, target joint velocity will be set to zero and wait for next command.

Parameters
timeThe current time.
periodThe time passed since the last call to update.

Implements controller_interface::ControllerBase.

Definition at line 112 of file mechanical_calibration_controller.cpp.

Member Data Documentation

◆ countdown_

int rm_calibration_controllers::MechanicalCalibrationController::countdown_ {}
private

Definition at line 143 of file mechanical_calibration_controller.h.

◆ is_center_

bool rm_calibration_controllers::MechanicalCalibrationController::is_center_ {}
private

Definition at line 146 of file mechanical_calibration_controller.h.

◆ is_return_

bool rm_calibration_controllers::MechanicalCalibrationController::is_return_ {}
private

Definition at line 146 of file mechanical_calibration_controller.h.

◆ negative_position_

double rm_calibration_controllers::MechanicalCalibrationController::negative_position_ {}
private

Definition at line 145 of file mechanical_calibration_controller.h.

◆ position_threshold_

double rm_calibration_controllers::MechanicalCalibrationController::position_threshold_ {}
private

Definition at line 144 of file mechanical_calibration_controller.h.

◆ positive_position_

double rm_calibration_controllers::MechanicalCalibrationController::positive_position_ {}
private

Definition at line 145 of file mechanical_calibration_controller.h.

◆ target_position_

double rm_calibration_controllers::MechanicalCalibrationController::target_position_ {}
private

Definition at line 145 of file mechanical_calibration_controller.h.

◆ velocity_threshold_

double rm_calibration_controllers::MechanicalCalibrationController::velocity_threshold_ {}
private

Definition at line 144 of file mechanical_calibration_controller.h.


The documentation for this class was generated from the following files:


rm_calibration_controllers
Author(s): Qiayuan Liao
autogenerated on Sun Apr 13 2025 02:56:24