#include <calibration_base.h>
Public Member Functions | |
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 |
![]() | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &) |
MultiInterfaceController (bool allow_optional_interfaces=false) | |
![]() | |
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 |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (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) |
virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
virtual void | update (const ros::Time &time, const ros::Duration &period)=0 |
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 |
Protected Types | |
enum | State { INITIALIZED, CALIBRATED } |
Protected Member Functions | |
bool | isCalibrated (control_msgs::QueryCalibrationState::Request &req, control_msgs::QueryCalibrationState::Response &resp) |
Provide a service to know the state of target actuators. More... | |
![]() | |
bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
Protected Attributes | |
rm_control::ActuatorExtraHandle | actuator_ |
bool | calibration_success_ = false |
ros::ServiceServer | is_calibrated_srv_ |
effort_controllers::JointPositionController | position_ctrl_ |
int | state_ {} |
effort_controllers::JointVelocityController | velocity_ctrl_ |
double | velocity_search_ {} |
![]() | |
bool | allow_optional_interfaces_ |
hardware_interface::RobotHW | robot_hw_ctrl_ |
Additional Inherited Members | |
![]() | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
enum | ControllerState { ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED, ControllerState::WAITING, ControllerState::ABORTED } |
![]() | |
ControllerState | state_ |
![]() | |
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) |
Definition at line 20 of file calibration_base.h.
|
protected |
Enumerator | |
---|---|
INITIALIZED | |
CALIBRATED |
Definition at line 58 of file calibration_base.h.
|
default |
|
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.
robot_hw | The robot hardware abstraction. |
root_nh | A NodeHandle in the root of the controller manager namespace. This is where the ROS interfaces are setup (publishers, subscribers, services). |
controller_nh | A NodeHandle in the namespace of the controller. This is where the controller-specific configuration resides. |
Reimplemented from controller_interface::MultiInterfaceController< T... >.
Definition at line 14 of file calibration_base.cpp.
|
protected |
Provide a service to know the state of target actuators.
When requesting to this server, it will return respond about whether target actuators has been calibrated.
req | The request of knowing the state of target actuators. |
resp | The respond included the state of target actuators. |
Definition at line 53 of file calibration_base.cpp.
|
overridevirtual |
Switch all of the actuators state to INITIALIZED.
Switch all of the actuator state to INITIALIZED in order to restart the calibration.
time | The current time. |
Reimplemented from controller_interface::ControllerBase.
Definition at line 37 of file calibration_base.cpp.
|
overridevirtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 47 of file calibration_base.cpp.
|
protected |
Definition at line 66 of file calibration_base.h.
|
protected |
Definition at line 65 of file calibration_base.h.
|
protected |
Definition at line 57 of file calibration_base.h.
|
protected |
Definition at line 68 of file calibration_base.h.
|
protected |
Definition at line 63 of file calibration_base.h.
|
protected |
Definition at line 67 of file calibration_base.h.
|
protected |
Definition at line 64 of file calibration_base.h.