#include <srh_mixed_position_velocity_controller.hpp>
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::RobotState *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. | |
Private Member Functions | |
void | read_parameters () |
read all the controller settings from the parameter server | |
void | resetJointState () |
void | setCommandCB (const std_msgs::Float64ConstPtr &msg) |
set the position target from a topic | |
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. | |
double | max_velocity_ |
The values for the velocity demand saturation. | |
double | min_velocity_ |
int | motor_min_force_threshold |
smallest demand we can send to the motors | |
boost::scoped_ptr < control_toolbox::Pid > | pid_controller_position_ |
boost::scoped_ptr < control_toolbox::Pid > | pid_controller_velocity_ |
double | position_deadband |
the deadband on the position demand | |
ros::ServiceServer | serve_set_gains_ |
Definition at line 39 of file srh_mixed_position_velocity_controller.hpp.
Definition at line 45 of file srh_mixed_position_velocity_controller.cpp.
void controller::SrhMixedPositionVelocityJointController::getGains | ( | double & | p, |
double & | i, | ||
double & | d, | ||
double & | i_max, | ||
double & | i_min | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 212 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 217 of file srh_mixed_position_velocity_controller.cpp.
bool controller::SrhMixedPositionVelocityJointController::init | ( | ros_ethercat_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Implements controller::SrController.
Definition at line 51 of file srh_mixed_position_velocity_controller.cpp.
void controller::SrhMixedPositionVelocityJointController::read_parameters | ( | ) | [private] |
read all the controller settings from the parameter server
Definition at line 356 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 192 of file srh_mixed_position_velocity_controller.cpp.
void controller::SrhMixedPositionVelocityJointController::resetJointState | ( | ) | [private] |
Definition at line 374 of file srh_mixed_position_velocity_controller.cpp.
void controller::SrhMixedPositionVelocityJointController::setCommandCB | ( | const std_msgs::Float64ConstPtr & | msg | ) | [private, virtual] |
set the position target from a topic
Reimplemented from controller::SrController.
Definition at line 367 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 154 of file srh_mixed_position_velocity_controller.cpp.
void controller::SrhMixedPositionVelocityJointController::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 141 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 222 of file srh_mixed_position_velocity_controller.cpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller::SrhMixedPositionVelocityJointController::controller_state_publisher_ [private] |
Reimplemented from controller::SrController.
Definition at line 64 of file srh_mixed_position_velocity_controller.hpp.
sr_deadband::HysteresisDeadband<double> controller::SrhMixedPositionVelocityJointController::hysteresis_deadband [private] |
We're using an hysteresis deadband.
Reimplemented from controller::SrController.
Definition at line 82 of file srh_mixed_position_velocity_controller.hpp.
double controller::SrhMixedPositionVelocityJointController::max_velocity_ [private] |
The values for the velocity demand saturation.
Definition at line 67 of file srh_mixed_position_velocity_controller.hpp.
double controller::SrhMixedPositionVelocityJointController::min_velocity_ [private] |
Definition at line 67 of file srh_mixed_position_velocity_controller.hpp.
smallest demand we can send to the motors
Definition at line 88 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 60 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 61 of file srh_mixed_position_velocity_controller.hpp.
the deadband on the position demand
Definition at line 79 of file srh_mixed_position_velocity_controller.hpp.
Reimplemented from controller::SrController.
Definition at line 76 of file srh_mixed_position_velocity_controller.hpp.