38 #include <std_msgs/Float64.h> 49 SrhMixedPositionVelocityJointController::SrhMixedPositionVelocityJointController()
50 : max_velocity_(1.0), min_velocity_(-1.0), prev_in_deadband_(false),
51 maintained_command_(0.0), override_to_current_effort_(false),
52 position_deadband(0.05), motor_min_force_threshold(0)
61 std::string robot_state_name;
62 node_.
param<std::string>(
"robot_state_name", robot_state_name,
"unique_robot_hw");
66 robot_ = robot->getHandle(robot_state_name).getState();
70 ROS_ERROR_STREAM(
"Could not find robot state: " << robot_state_name <<
" Not loading the controller. " <<
108 ROS_ERROR(
"SrhMixedPositionVelocityController could not find the first joint relevant to \"%s\"\n",
114 ROS_ERROR(
"SrhMixedPositionVelocityController could not find the second joint relevant to \"%s\"\n",
120 ROS_ERROR(
"Joint %s not calibrated for SrhMixedPositionVelocityController",
joint_name_.c_str());
133 ROS_ERROR(
"SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
139 ROS_ERROR(
"Joint %s not calibrated for SrhMixedPositionVelocityJointController",
joint_name_.c_str());
156 #ifdef DEBUG_PUBLISHER 159 ROS_INFO(
"Publishing debug info for FFJ3 mixed position/velocity controller");
185 sr_robot_msgs::SetMixedPositionVelocityPidGains::Response
189 "New parameters: " <<
"PID pos: [" << req.position_p <<
", " << req.position_i <<
", " << req.position_d <<
190 ", " << req.position_i_clamp <<
"] PID vel: [" << req.velocity_p <<
", " << req.velocity_i <<
", " <<
191 req.velocity_d <<
", " << req.velocity_i_clamp <<
"], max force: " << req.max_force <<
192 ", friction deadband: " << req.friction_deadband <<
" pos deadband: " << req.position_deadband <<
193 " min and max vel: [" << req.min_velocity <<
", " << req.max_velocity <<
"]");
196 double p, i,
d, i_max, i_min;
201 -req.position_i_clamp);
204 -req.velocity_i_clamp, antiwindup);
217 node_.
setParam(
"position_pid/i_clamp", req.position_i_clamp);
222 node_.
setParam(
"velocity_pid/i_clamp", req.velocity_i_clamp);
237 std_srvs::Empty::Response &resp)
302 double error_position = 0.0;
318 error_position = 0.0;
322 double commanded_velocity = 0.0;
323 double error_velocity = 0.0;
324 double commanded_effort = 0.0;
346 error_velocity = commanded_velocity -
joint_state_->velocity_;
375 commanded_effort = max(commanded_effort, -(
max_force_demand * max_force_factor_));
378 int friction_offset = 0;
390 static_cast<int>(commanded_effort),
394 commanded_effort += friction_offset;
401 commanded_effort = 0.0;
461 if (override_to_current_effort_)
void get_min_max(urdf::Model model, std::string joint_name)
bool prev_in_deadband_
Stores if was previously in the deadband.
virtual const char * what() const
ros_ethercat_model::JointState * joint_state_
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
double maintained_command_
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
void read_parameters()
read all the controller settings from the parameter server
Compute a velocity demand from the position error using a PID loop. The velocity demand is then conve...
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
ros_ethercat_model::JointState * joint_state_2
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min)
double clamp_command(double cmd, double min_cmd, double max_cmd)
ros_ethercat_model::RobotState * robot_
bool override_to_current_effort_
Override commanded_effort to current effort when in deadband.
double position_deadband
the deadband on the position demand
int friction_deadband
the deadband for the friction compensation algorithm
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string & getNamespace() const
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We're using an hysteresis deadband.
ros::ServiceServer serve_set_gains_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getJointName()
bool is_in_deadband(T demand, T error, T deadband, double deadband_multiplicator=5.0, unsigned int nb_errors_for_avg=50)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
double max_force_demand
clamps the force demand to this value
virtual void starting(const ros::Time &time)
void get_joints_states_1_2()
#define ROS_INFO_STREAM(args)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
bool getParam(const std::string &key, std::string &s) const
int motor_min_force_threshold
smallest demand we can send to the motors
#define ROS_ERROR_STREAM(args)
bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
double max_velocity_
The values for the velocity demand saturation.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_
void after_init()
call this function at the end of the init function in the inheriting classes.
ros::ServiceServer serve_reset_gains_