36 #include <std_msgs/Float64.h> 46 SrhJointPositionController::SrhJointPositionController()
47 : position_deadband(0.015)
55 std::string robot_state_name;
56 node_.
param<std::string>(
"robot_state_name", robot_state_name,
"unique_robot_hw");
60 robot_ = robot->getHandle(robot_state_name).getState();
64 ROS_ERROR_STREAM(
"Could not find robot state: " << robot_state_name <<
" Not loading the controller. " <<
96 ROS_ERROR(
"SrhJointPositionController could not find the first joint relevant to \"%s\"\n",
102 ROS_ERROR(
"SrhJointPositionController could not find the second joint relevant to \"%s\"\n",
121 ROS_ERROR(
"SrhJointPositionController could not find joint named \"%s\"\n",
joint_name_.c_str());
157 sr_robot_msgs::SetPidGains::Response &resp)
159 ROS_INFO_STREAM(
"Setting new PID parameters. P:" << req.p <<
" / I:" << req.i <<
160 " / D:" << req.d <<
" / IClamp:" << req.i_clamp <<
", max force: " <<
161 req.max_force <<
", friction deadband: " << req.friction_deadband <<
162 " pos deadband: " << req.deadband);
232 double error_position = 0.0;
233 double commanded_effort = 0.0;
249 error_position = 0.0;
256 commanded_effort = max(commanded_effort, -(
max_force_demand * max_force_factor_));
265 static_cast<int>(commanded_effort),
272 static_cast<int>(commanded_effort),
void get_min_max(urdf::Model model, std::string joint_name)
virtual const char * what() const
ros_ethercat_model::JointState * joint_state_
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We're using an hysteresis deadband.
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
double position_deadband
the position deadband value used in the hysteresis_deadband
void read_parameters()
read all the controller settings from the parameter server
virtual void starting(const ros::Time &time)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros_ethercat_model::JointState * joint_state_2
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
double clamp_command(double cmd, double min_cmd, double max_cmd)
ros_ethercat_model::RobotState * robot_
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
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
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
const std::string & getNamespace() const
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
void get_joints_states_1_2()
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer serve_set_gains_
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
#define ROS_ERROR_STREAM(args)
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
void after_init()
call this function at the end of the init function in the inheriting classes.
ros::ServiceServer serve_reset_gains_