Public Member Functions | List of all members
controller::SrhExampleController Class Reference

#include <srh_example_controller.hpp>

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

Public Member Functions

bool init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
 
bool init (ros_ethercat_model::RobotStateInterface *robot, const std::string &joint_name)
 
 SrhExampleController ()
 
virtual void starting (const ros::Time &time)
 
virtual void update (const ros::Time &time, const ros::Duration &period)
 
virtual ~SrhExampleController ()
 
- Public Member Functions inherited from controller::SrController
virtual void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 
std::string getJointName ()
 
virtual bool resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 
 SrController ()
 
virtual ~SrController ()
 
- 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 ()
 
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 ()
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller::SrController
double command_
 
bool has_j2
 
ros_ethercat_model::JointState * joint_state_
 
ros_ethercat_model::JointState * joint_state_2
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller::SrController
void after_init ()
 call this function at the end of the init function in the inheriting classes. More...
 
double clamp_command (double cmd, double min_cmd, double max_cmd)
 
virtual double clamp_command (double cmd)
 
void get_joints_states_1_2 ()
 
void get_min_max (urdf::Model model, std::string joint_name)
 
bool is_joint_0 ()
 
void maxForceFactorCB (const std_msgs::Float64ConstPtr &msg)
 
virtual void setCommandCB (const std_msgs::Float64ConstPtr &msg)
 set the command from a topic More...
 
- 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 inherited from controller::SrController
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
 
double eff_max_
 
double eff_min_
 Min and max range of the effort, used to clamp the command. More...
 
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensatorfriction_compensator
 
int friction_deadband
 the deadband for the friction compensation algorithm More...
 
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
 We're using an hysteresis deadband. More...
 
bool initialized_
 
std::string joint_name_
 
int loop_count_
 
double max_
 
double max_force_demand
 clamps the force demand to this value More...
 
double max_force_factor_
 
double min_
 Min and max range of the joint, used to clamp the command. More...
 
ros::NodeHandle n_tilde_
 
ros::NodeHandle node_
 
ros_ethercat_model::RobotState * robot_
 
ros::ServiceServer serve_reset_gains_
 
ros::ServiceServer serve_set_gains_
 
ros::Subscriber sub_command_
 
ros::Subscriber sub_max_force_factor_
 
double vel_max_
 
double vel_min_
 Min and max range of the velocity, used to clamp the command. More...
 

Detailed Description

Definition at line 36 of file srh_example_controller.hpp.

Constructor & Destructor Documentation

controller::SrhExampleController::SrhExampleController ( )

The controller manager will instanciate one instance of this class per controlled joint.

Definition at line 40 of file srh_example_controller.cpp.

controller::SrhExampleController::~SrhExampleController ( )
virtual

Destructor.

Definition at line 47 of file srh_example_controller.cpp.

Member Function Documentation

bool controller::SrhExampleController::init ( ros_ethercat_model::RobotStateInterface *  robot,
ros::NodeHandle n 
)
virtual

The first init is used to read which joint is being controlled from the parameter server.

Parameters
robotA pointer to the robot state, passed to the 2nd init function.
nThe ROS nodehandle, to be able to access the parameter server.
Returns
True if the 2nd init function succeeds.

Implements controller::SrController.

Definition at line 53 of file srh_example_controller.cpp.

bool controller::SrhExampleController::init ( ros_ethercat_model::RobotStateInterface *  robot,
const std::string &  joint_name 
)

This init funciton is called by the previous init function. It finishes to initalise the different necessary variables.

Parameters
robotA pointer to the robot state (used to get the joint_state)
joint_nameThe name of the joint which is controlled.
Returns
true if initialized.

Definition at line 79 of file srh_example_controller.cpp.

void controller::SrhExampleController::starting ( const ros::Time time)
virtual

This method is called when the controller is started. The command is then to be the current position (or effort / velocity / ... depending on what you're controlling), so that the first command won't move the joint.

Reimplemented from controller::SrController.

Definition at line 145 of file srh_example_controller.cpp.

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

Issues commands to the joint. This method is called at the specified rate by the main loop.

Implements controller::SrController.

Definition at line 158 of file srh_example_controller.cpp.


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