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

#include <srh_joint_muscle_valve_controller.hpp>

Inheritance diagram for controller::SrhJointMuscleValveController:
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)
 
 SrhJointMuscleValveController ()
 
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 >
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

unsigned int cmd_duration_ms_ [2]
 
int8_t cmd_valve_muscle_ [2]
 
int8_t cmd_valve_muscle_max_
 
int8_t cmd_valve_muscle_min_
 
unsigned int current_duration_ms_ [2]
 
- 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
 

Private Member Functions

int8_t clamp_command (int8_t cmd)
 enforce that the value of the received command is in the allowed range More...
 
void read_parameters ()
 read all the controller settings from the parameter server More...
 
void setCommandCB (const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg)
 

Private Attributes

boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMuscleValveControllerState > > controller_state_publisher_
 
ros::Subscriber sub_command_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- 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
 
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 39 of file srh_joint_muscle_valve_controller.hpp.

Constructor & Destructor Documentation

◆ SrhJointMuscleValveController()

controller::SrhJointMuscleValveController::SrhJointMuscleValveController ( )

Definition at line 44 of file srh_joint_muscle_valve_controller.cpp.

Member Function Documentation

◆ clamp_command()

int8_t controller::SrhJointMuscleValveController::clamp_command ( int8_t  cmd)
private

enforce that the value of the received command is in the allowed range

Definition at line 327 of file srh_joint_muscle_valve_controller.cpp.

◆ getGains()

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

Reimplemented from controller::SrController.

Definition at line 149 of file srh_joint_muscle_valve_controller.cpp.

◆ init()

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

Implements controller::SrController.

Definition at line 50 of file srh_joint_muscle_valve_controller.cpp.

◆ read_parameters()

void controller::SrhJointMuscleValveController::read_parameters ( )
private

read all the controller settings from the parameter server

Definition at line 309 of file srh_joint_muscle_valve_controller.cpp.

◆ resetGains()

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

Reimplemented from controller::SrController.

Definition at line 134 of file srh_joint_muscle_valve_controller.cpp.

◆ setCommandCB()

void controller::SrhJointMuscleValveController::setCommandCB ( const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &  msg)
private

Definition at line 313 of file srh_joint_muscle_valve_controller.cpp.

◆ starting()

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

Reimplemented from controller::SrController.

Definition at line 128 of file srh_joint_muscle_valve_controller.cpp.

◆ update()

void controller::SrhJointMuscleValveController::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 153 of file srh_joint_muscle_valve_controller.cpp.

Member Data Documentation

◆ cmd_duration_ms_

unsigned int controller::SrhJointMuscleValveController::cmd_duration_ms_[2]

Last duration commanded for the valve command for each muscle.

Definition at line 60 of file srh_joint_muscle_valve_controller.hpp.

◆ cmd_valve_muscle_

int8_t controller::SrhJointMuscleValveController::cmd_valve_muscle_[2]

Last commanded valve values for each muscle.

Definition at line 58 of file srh_joint_muscle_valve_controller.hpp.

◆ cmd_valve_muscle_max_

int8_t controller::SrhJointMuscleValveController::cmd_valve_muscle_max_

Definition at line 65 of file srh_joint_muscle_valve_controller.hpp.

◆ cmd_valve_muscle_min_

int8_t controller::SrhJointMuscleValveController::cmd_valve_muscle_min_

Definition at line 64 of file srh_joint_muscle_valve_controller.hpp.

◆ controller_state_publisher_

boost::shared_ptr<realtime_tools::RealtimePublisher <sr_robot_msgs::JointMuscleValveControllerState> > controller::SrhJointMuscleValveController::controller_state_publisher_
private

Definition at line 70 of file srh_joint_muscle_valve_controller.hpp.

◆ current_duration_ms_

unsigned int controller::SrhJointMuscleValveController::current_duration_ms_[2]

Definition at line 62 of file srh_joint_muscle_valve_controller.hpp.

◆ sub_command_

ros::Subscriber controller::SrhJointMuscleValveController::sub_command_
private

Definition at line 72 of file srh_joint_muscle_valve_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