#include <srh_joint_position_controller.hpp>
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) |
SrhJointPositionController () | |
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 | |
sr_deadband::HysteresisDeadband< double > | hysteresis_deadband |
We're using an hysteresis deadband. More... | |
boost::scoped_ptr< control_toolbox::Pid > | pid_controller_position_ |
Internal PID controller for the position loop. More... | |
double | position_deadband |
the position deadband value used in the hysteresis_deadband More... | |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
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::SrFrictionCompensator > | friction_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... | |
Definition at line 36 of file srh_joint_position_controller.hpp.
controller::SrhJointPositionController::SrhJointPositionController | ( | ) |
Definition at line 46 of file srh_joint_position_controller.cpp.
|
virtual |
Reimplemented from controller::SrController.
Definition at line 201 of file srh_joint_position_controller.cpp.
|
virtual |
Implements controller::SrController.
Definition at line 51 of file srh_joint_position_controller.cpp.
|
private |
read all the controller settings from the parameter server
Definition at line 312 of file srh_joint_position_controller.cpp.
|
virtual |
Reimplemented from controller::SrController.
Definition at line 181 of file srh_joint_position_controller.cpp.
|
private |
Definition at line 328 of file srh_joint_position_controller.cpp.
|
privatevirtual |
set the position target from a topic
Reimplemented from controller::SrController.
Definition at line 319 of file srh_joint_position_controller.cpp.
bool controller::SrhJointPositionController::setGains | ( | sr_robot_msgs::SetPidGains::Request & | req, |
sr_robot_msgs::SetPidGains::Response & | resp | ||
) |
Definition at line 156 of file srh_joint_position_controller.cpp.
|
virtual |
Reimplemented from controller::SrController.
Definition at line 143 of file srh_joint_position_controller.cpp.
|
virtual |
Issues commands to the joint. Should be called at regular intervals.
Implements controller::SrController.
Definition at line 206 of file srh_joint_position_controller.cpp.
|
private |
We're using an hysteresis deadband.
Definition at line 65 of file srh_joint_position_controller.hpp.
|
private |
Internal PID controller for the position loop.
Definition at line 59 of file srh_joint_position_controller.hpp.
|
private |
the position deadband value used in the hysteresis_deadband
Definition at line 62 of file srh_joint_position_controller.hpp.