Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
controller::SrController Class Referenceabstract

#include <sr_controller.hpp>

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

Public Member Functions

virtual void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 
std::string getJointName ()
 
virtual bool init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)=0
 
virtual bool resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
 
 SrController ()
 
virtual void starting (const ros::Time &time)
 
virtual void update (const ros::Time &time, const ros::Duration &period)=0
 Issues commands to the joint. Should be called at regular intervals. More...
 
virtual ~SrController ()
 
- Public Member Functions inherited from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- 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)
 
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 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
 

Public Attributes

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
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 

Protected Member Functions

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
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Protected Attributes

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...
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 

Detailed Description

Definition at line 54 of file sr_controller.hpp.

Constructor & Destructor Documentation

◆ SrController()

controller::SrController::SrController ( )

Definition at line 40 of file sr_controller.cpp.

◆ ~SrController()

controller::SrController::~SrController ( )
virtual

Definition at line 61 of file sr_controller.cpp.

Member Function Documentation

◆ after_init()

void controller::SrController::after_init ( )
protected

call this function at the end of the init function in the inheriting classes.

Definition at line 89 of file sr_controller.cpp.

◆ clamp_command() [1/2]

double controller::SrController::clamp_command ( double  cmd,
double  min_cmd,
double  max_cmd 
)
protected

Clamps the command to the correct range (between min_cmd and max_cmd).

Parameters
cmdthe command we want to clamp
min_cmdthe min to clamp to
max_cmdthe max to clamp to
Returns
the clamped command

Definition at line 133 of file sr_controller.cpp.

◆ clamp_command() [2/2]

double controller::SrController::clamp_command ( double  cmd)
protectedvirtual

Clamps the command to the correct range (between angular min and max).

Parameters
cmdthe command we want to clamp
Returns
the clamped command

Reimplemented in controller::SrhJointVelocityController, and controller::SrhEffortJointController.

Definition at line 146 of file sr_controller.cpp.

◆ get_joints_states_1_2()

void controller::SrController::get_joints_states_1_2 ( )
protected

Definition at line 77 of file sr_controller.cpp.

◆ get_min_max()

void controller::SrController::get_min_max ( urdf::Model  model,
std::string  joint_name 
)
protected

Reads the min and max from the robot model for the current joint.

Parameters
modelthe urdf description of the robot
joint_namethe name of the joint

Definition at line 101 of file sr_controller.cpp.

◆ getGains()

virtual void controller::SrController::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)
inlinevirtual

◆ getJointName()

std::string controller::SrController::getJointName ( )

Definition at line 96 of file sr_controller.cpp.

◆ init()

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

◆ is_joint_0()

bool controller::SrController::is_joint_0 ( )
protected

Definition at line 66 of file sr_controller.cpp.

◆ maxForceFactorCB()

void controller::SrController::maxForceFactorCB ( const std_msgs::Float64ConstPtr &  msg)
protected

Callback function for the max force factor topic

Parameters
msgthe message receiver over the topic

Definition at line 151 of file sr_controller.cpp.

◆ resetGains()

virtual bool controller::SrController::resetGains ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  resp 
)
inlinevirtual

◆ setCommandCB()

virtual void controller::SrController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg)
inlineprotectedvirtual

◆ starting()

virtual void controller::SrController::starting ( const ros::Time time)
inlinevirtual

◆ update()

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

Member Data Documentation

◆ command_

double controller::SrController::command_

Last commanded position.

Definition at line 90 of file sr_controller.hpp.

◆ controller_state_publisher_

boost::scoped_ptr<realtime_tools::RealtimePublisher <control_msgs::JointControllerState> > controller::SrController::controller_state_publisher_
protected

Definition at line 149 of file sr_controller.hpp.

◆ eff_max_

double controller::SrController::eff_max_
protected

Definition at line 138 of file sr_controller.hpp.

◆ eff_min_

double controller::SrController::eff_min_
protected

Min and max range of the effort, used to clamp the command.

Definition at line 138 of file sr_controller.hpp.

◆ friction_compensator

boost::scoped_ptr<sr_friction_compensation::SrFrictionCompensator> controller::SrController::friction_compensator
protected

Definition at line 151 of file sr_controller.hpp.

◆ friction_deadband

int controller::SrController::friction_deadband
protected

the deadband for the friction compensation algorithm

Definition at line 165 of file sr_controller.hpp.

◆ has_j2

bool controller::SrController::has_j2

true if this is a joint 0.

Definition at line 88 of file sr_controller.hpp.

◆ hysteresis_deadband

sr_deadband::HysteresisDeadband<double> controller::SrController::hysteresis_deadband
protected

We're using an hysteresis deadband.

Definition at line 168 of file sr_controller.hpp.

◆ initialized_

bool controller::SrController::initialized_
protected

Definition at line 141 of file sr_controller.hpp.

◆ joint_name_

std::string controller::SrController::joint_name_
protected

Definition at line 146 of file sr_controller.hpp.

◆ joint_state_

ros_ethercat_model::JointState* controller::SrController::joint_state_

Joint we're controlling.

Definition at line 84 of file sr_controller.hpp.

◆ joint_state_2

ros_ethercat_model::JointState* controller::SrController::joint_state_2

2ndJoint we're controlling if joint 0.

Definition at line 86 of file sr_controller.hpp.

◆ loop_count_

int controller::SrController::loop_count_
protected

Definition at line 140 of file sr_controller.hpp.

◆ max_

double controller::SrController::max_
protected

Definition at line 134 of file sr_controller.hpp.

◆ max_force_demand

double controller::SrController::max_force_demand
protected

clamps the force demand to this value

Definition at line 163 of file sr_controller.hpp.

◆ max_force_factor_

double controller::SrController::max_force_factor_
protected

Definition at line 174 of file sr_controller.hpp.

◆ min_

double controller::SrController::min_
protected

Min and max range of the joint, used to clamp the command.

Definition at line 134 of file sr_controller.hpp.

◆ n_tilde_

ros::NodeHandle controller::SrController::n_tilde_
protected

Definition at line 145 of file sr_controller.hpp.

◆ node_

ros::NodeHandle controller::SrController::node_
protected

Definition at line 145 of file sr_controller.hpp.

◆ robot_

ros_ethercat_model::RobotState* controller::SrController::robot_
protected

Pointer to robot structure.

Definition at line 142 of file sr_controller.hpp.

◆ serve_reset_gains_

ros::ServiceServer controller::SrController::serve_reset_gains_
protected

Definition at line 160 of file sr_controller.hpp.

◆ serve_set_gains_

ros::ServiceServer controller::SrController::serve_set_gains_
protected

Definition at line 159 of file sr_controller.hpp.

◆ sub_command_

ros::Subscriber controller::SrController::sub_command_
protected

Definition at line 158 of file sr_controller.hpp.

◆ sub_max_force_factor_

ros::Subscriber controller::SrController::sub_max_force_factor_
protected

Definition at line 175 of file sr_controller.hpp.

◆ vel_max_

double controller::SrController::vel_max_
protected

Definition at line 136 of file sr_controller.hpp.

◆ vel_min_

double controller::SrController::vel_min_
protected

Min and max range of the velocity, used to clamp the command.

Definition at line 136 of file sr_controller.hpp.


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


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:31