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

#include <srh_mixed_position_velocity_controller.hpp>

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

Public Member Functions

virtual void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 
virtual void getGains_velocity (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::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
 
 SrhMixedPositionVelocityJointController ()
 
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...
 
- 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 >
 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 ()
 

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

boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_
 
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
 We're using an hysteresis deadband. More...
 
double maintained_command_
 
double max_velocity_
 The values for the velocity demand saturation. More...
 
double min_velocity_
 
int motor_min_force_threshold
 smallest demand we can send to the motors More...
 
bool override_to_current_effort_
 Override commanded_effort to current effort when in deadband. More...
 
boost::scoped_ptr< control_toolbox::Pidpid_controller_position_
 Internal PID controller for the position loop. More...
 
boost::scoped_ptr< control_toolbox::Pidpid_controller_velocity_
 Internal PID controller for the velocity loop. More...
 
double position_deadband
 the deadband on the position demand More...
 
bool prev_in_deadband_
 Stores if was previously in the deadband. More...
 
ros::ServiceServer serve_set_gains_
 

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)
 
- 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 39 of file srh_mixed_position_velocity_controller.hpp.

Constructor & Destructor Documentation

controller::SrhMixedPositionVelocityJointController::SrhMixedPositionVelocityJointController ( )

Definition at line 49 of file srh_mixed_position_velocity_controller.cpp.

Member Function Documentation

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

Reimplemented from controller::SrController.

Definition at line 262 of file srh_mixed_position_velocity_controller.cpp.

void controller::SrhMixedPositionVelocityJointController::getGains_velocity ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)
virtual

Definition at line 267 of file srh_mixed_position_velocity_controller.cpp.

bool controller::SrhMixedPositionVelocityJointController::init ( ros_ethercat_model::RobotStateInterface *  robot,
ros::NodeHandle n 
)
virtual
void controller::SrhMixedPositionVelocityJointController::read_parameters ( )
private

read all the controller settings from the parameter server

Definition at line 451 of file srh_mixed_position_velocity_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 236 of file srh_mixed_position_velocity_controller.cpp.

void controller::SrhMixedPositionVelocityJointController::resetJointState ( )
private

Definition at line 474 of file srh_mixed_position_velocity_controller.cpp.

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

set the position target from a topic

Reimplemented from controller::SrController.

Definition at line 465 of file srh_mixed_position_velocity_controller.cpp.

bool controller::SrhMixedPositionVelocityJointController::setGains ( sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &  req,
sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &  resp 
)

Definition at line 184 of file srh_mixed_position_velocity_controller.cpp.

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

Reimplemented from controller::SrController.

Definition at line 170 of file srh_mixed_position_velocity_controller.cpp.

void controller::SrhMixedPositionVelocityJointController::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 273 of file srh_mixed_position_velocity_controller.cpp.

Member Data Documentation

boost::scoped_ptr<realtime_tools::RealtimePublisher <sr_robot_msgs::JointControllerState> > controller::SrhMixedPositionVelocityJointController::controller_state_publisher_
private

Definition at line 71 of file srh_mixed_position_velocity_controller.hpp.

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

We're using an hysteresis deadband.

Definition at line 91 of file srh_mixed_position_velocity_controller.hpp.

double controller::SrhMixedPositionVelocityJointController::maintained_command_
private

Definition at line 78 of file srh_mixed_position_velocity_controller.hpp.

double controller::SrhMixedPositionVelocityJointController::max_velocity_
private

The values for the velocity demand saturation.

Definition at line 74 of file srh_mixed_position_velocity_controller.hpp.

double controller::SrhMixedPositionVelocityJointController::min_velocity_
private

Definition at line 74 of file srh_mixed_position_velocity_controller.hpp.

int controller::SrhMixedPositionVelocityJointController::motor_min_force_threshold
private

smallest demand we can send to the motors

Definition at line 97 of file srh_mixed_position_velocity_controller.hpp.

bool controller::SrhMixedPositionVelocityJointController::override_to_current_effort_
private

Override commanded_effort to current effort when in deadband.

Definition at line 80 of file srh_mixed_position_velocity_controller.hpp.

boost::scoped_ptr<control_toolbox::Pid> controller::SrhMixedPositionVelocityJointController::pid_controller_position_
private

Internal PID controller for the position loop.

Definition at line 65 of file srh_mixed_position_velocity_controller.hpp.

boost::scoped_ptr<control_toolbox::Pid> controller::SrhMixedPositionVelocityJointController::pid_controller_velocity_
private

Internal PID controller for the velocity loop.

Definition at line 67 of file srh_mixed_position_velocity_controller.hpp.

double controller::SrhMixedPositionVelocityJointController::position_deadband
private

the deadband on the position demand

Definition at line 88 of file srh_mixed_position_velocity_controller.hpp.

bool controller::SrhMixedPositionVelocityJointController::prev_in_deadband_
private

Stores if was previously in the deadband.

Definition at line 77 of file srh_mixed_position_velocity_controller.hpp.

ros::ServiceServer controller::SrhMixedPositionVelocityJointController::serve_set_gains_
private

Definition at line 85 of file srh_mixed_position_velocity_controller.hpp.


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