Public Member Functions | Private Member Functions | Private Attributes | List of all members
controller::SrhJointVariablePidPositionController Class Reference

#include <srh_joint_variable_pid_position_controller.hpp>

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

Public Member Functions

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

Private Member Functions

void read_parameters ()
 read all the controller settings from the parameter server More...
 
void resetJointState ()
 
void setCommandCB (const std_msgs::Float64ConstPtr &msg)
 set the position target from a topic More...
 

Private Attributes

double d_init_
 
double error_old_
 
double frequency_
 
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
 We're using an hysteresis deadband. More...
 
double i_clamp_
 
double i_init_
 
double p_init_
 initial PID parameters More...
 
boost::scoped_ptr< PlainPidpid_controller_position_
 Internal PID controller for the position loop. More...
 
double position_deadband_
 the position deadband value used in the hysteresis_deadband More...
 
double set_point_old_
 
double smoothing_factor_d_
 
double smoothing_factor_i_
 
double smoothing_factor_p_
 
double smoothing_velocity_max_
 
double smoothing_velocity_min_
 

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
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 
- 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)
 
- 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 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 38 of file srh_joint_variable_pid_position_controller.hpp.

Constructor & Destructor Documentation

◆ SrhJointVariablePidPositionController()

controller::SrhJointVariablePidPositionController::SrhJointVariablePidPositionController ( )

Member Function Documentation

◆ getGains()

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

Reimplemented from controller::SrController.

Definition at line 206 of file srh_joint_variable_pid_position_controller.cpp.

◆ init()

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

◆ read_parameters()

void controller::SrhJointVariablePidPositionController::read_parameters ( )
private

read all the controller settings from the parameter server

Definition at line 344 of file srh_joint_variable_pid_position_controller.cpp.

◆ resetGains()

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

Reimplemented from controller::SrController.

Definition at line 186 of file srh_joint_variable_pid_position_controller.cpp.

◆ resetJointState()

void controller::SrhJointVariablePidPositionController::resetJointState ( )
private

◆ setCommandCB()

void controller::SrhJointVariablePidPositionController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg)
privatevirtual

set the position target from a topic

Reimplemented from controller::SrController.

Definition at line 351 of file srh_joint_variable_pid_position_controller.cpp.

◆ setGains()

bool controller::SrhJointVariablePidPositionController::setGains ( sr_robot_msgs::SetPidGains::Request &  req,
sr_robot_msgs::SetPidGains::Response &  resp 
)

◆ starting()

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

Reimplemented from controller::SrController.

Definition at line 144 of file srh_joint_variable_pid_position_controller.cpp.

◆ update()

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

Issues commands to the joint. Should be called at regular intervals.

Implements controller::SrController.

Definition at line 241 of file srh_joint_variable_pid_position_controller.cpp.

◆ updatePid()

void controller::SrhJointVariablePidPositionController::updatePid ( double  error,
double  set_point 
)
virtual

Member Data Documentation

◆ d_init_

double controller::SrhJointVariablePidPositionController::d_init_
private

◆ error_old_

double controller::SrhJointVariablePidPositionController::error_old_
private

◆ frequency_

double controller::SrhJointVariablePidPositionController::frequency_
private

◆ hysteresis_deadband

sr_deadband::HysteresisDeadband<double> controller::SrhJointVariablePidPositionController::hysteresis_deadband
private

We're using an hysteresis deadband.

Definition at line 83 of file srh_joint_variable_pid_position_controller.hpp.

◆ i_clamp_

double controller::SrhJointVariablePidPositionController::i_clamp_
private

◆ i_init_

double controller::SrhJointVariablePidPositionController::i_init_
private

◆ p_init_

double controller::SrhJointVariablePidPositionController::p_init_
private

initial PID parameters

Definition at line 69 of file srh_joint_variable_pid_position_controller.hpp.

◆ pid_controller_position_

boost::scoped_ptr<PlainPid> controller::SrhJointVariablePidPositionController::pid_controller_position_
private

Internal PID controller for the position loop.

Definition at line 63 of file srh_joint_variable_pid_position_controller.hpp.

◆ position_deadband_

double controller::SrhJointVariablePidPositionController::position_deadband_
private

the position deadband value used in the hysteresis_deadband

Definition at line 66 of file srh_joint_variable_pid_position_controller.hpp.

◆ set_point_old_

double controller::SrhJointVariablePidPositionController::set_point_old_
private

◆ smoothing_factor_d_

double controller::SrhJointVariablePidPositionController::smoothing_factor_d_
private

◆ smoothing_factor_i_

double controller::SrhJointVariablePidPositionController::smoothing_factor_i_
private

◆ smoothing_factor_p_

double controller::SrhJointVariablePidPositionController::smoothing_factor_p_
private

◆ smoothing_velocity_max_

double controller::SrhJointVariablePidPositionController::smoothing_velocity_max_
private

◆ smoothing_velocity_min_

double controller::SrhJointVariablePidPositionController::smoothing_velocity_min_
private

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