Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
controller::SrhFakeJointCalibrationController Class Reference

#include <srh_fake_joint_calibration_controller.h>

Inheritance diagram for controller::SrhFakeJointCalibrationController:
Inheritance graph
[legend]

Public Member Functions

void beginCalibration ()
 
bool calibrated ()
 
virtual bool init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
 
 SrhFakeJointCalibrationController ()
 
virtual void update (const ros::Time &time, const ros::Duration &period)
 
- Public Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >
 Controller ()
 
virtual bool init (ros_ethercat_model::RobotStateInterface *, ros::NodeHandle &, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
virtual void starting (const ros::Time &)
 
virtual void starting (const ros::Time &)
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::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 ~ControllerBase ()
 

Protected Types

enum  {
  IS_INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH,
  CALIBRATED
}
 

Protected Member Functions

void initialize_pids ()
 
- Protected Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >
std::string getHardwareInterfaceType () const
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

Protected Attributes

ros_ethercat_model::Actuator * actuator_
 
std::string actuator_name_
 
int calibration_state_
 
ros_ethercat_model::JointState * joint_
 
std::string joint_name_
 
std::string joint_prefix_
 
ros::Time last_publish_time_
 
ros::NodeHandle node_
 
std::string ns_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
 
ros_ethercat_model::RobotState * robot_
 
std::string robot_id_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 

Detailed Description

Definition at line 43 of file srh_fake_joint_calibration_controller.h.

Member Enumeration Documentation

anonymous enum
protected
Enumerator
IS_INITIALIZED 
BEGINNING 
MOVING_TO_LOW 
MOVING_TO_HIGH 
CALIBRATED 

Definition at line 72 of file srh_fake_joint_calibration_controller.h.

Constructor & Destructor Documentation

controller::SrhFakeJointCalibrationController::SrhFakeJointCalibrationController ( )

Definition at line 40 of file srh_fake_joint_calibration_controller.cpp.

Member Function Documentation

void controller::SrhFakeJointCalibrationController::beginCalibration ( )
inline

Definition at line 58 of file srh_fake_joint_calibration_controller.h.

bool controller::SrhFakeJointCalibrationController::calibrated ( )
inline

Definition at line 53 of file srh_fake_joint_calibration_controller.h.

bool controller::SrhFakeJointCalibrationController::init ( ros_ethercat_model::RobotStateInterface *  robot,
ros::NodeHandle n 
)
virtual
void controller::SrhFakeJointCalibrationController::initialize_pids ( )
protected

Read the pids values from the parameter server and calls the service to set them on the hand.

Definition at line 155 of file srh_fake_joint_calibration_controller.cpp.

void controller::SrhFakeJointCalibrationController::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Member Data Documentation

ros_ethercat_model::Actuator* controller::SrhFakeJointCalibrationController::actuator_
protected

Definition at line 78 of file srh_fake_joint_calibration_controller.h.

std::string controller::SrhFakeJointCalibrationController::actuator_name_
protected

Definition at line 81 of file srh_fake_joint_calibration_controller.h.

int controller::SrhFakeJointCalibrationController::calibration_state_
protected

Definition at line 76 of file srh_fake_joint_calibration_controller.h.

ros_ethercat_model::JointState* controller::SrhFakeJointCalibrationController::joint_
protected

Definition at line 79 of file srh_fake_joint_calibration_controller.h.

std::string controller::SrhFakeJointCalibrationController::joint_name_
protected

Definition at line 81 of file srh_fake_joint_calibration_controller.h.

std::string controller::SrhFakeJointCalibrationController::joint_prefix_
protected

Definition at line 81 of file srh_fake_joint_calibration_controller.h.

ros::Time controller::SrhFakeJointCalibrationController::last_publish_time_
protected

Definition at line 70 of file srh_fake_joint_calibration_controller.h.

ros::NodeHandle controller::SrhFakeJointCalibrationController::node_
protected

Definition at line 68 of file srh_fake_joint_calibration_controller.h.

std::string controller::SrhFakeJointCalibrationController::ns_
protected

Definition at line 81 of file srh_fake_joint_calibration_controller.h.

boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > controller::SrhFakeJointCalibrationController::pub_calibrated_
protected

Definition at line 69 of file srh_fake_joint_calibration_controller.h.

ros_ethercat_model::RobotState* controller::SrhFakeJointCalibrationController::robot_
protected

Definition at line 67 of file srh_fake_joint_calibration_controller.h.

std::string controller::SrhFakeJointCalibrationController::robot_id_
protected

Definition at line 81 of file srh_fake_joint_calibration_controller.h.


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


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58