38 #include <std_msgs/Float64.h> 47 bool SrhEffortJointController::init(ros_ethercat_model::RobotStateInterface *robot,
ros::NodeHandle &n)
51 std::string robot_state_name;
52 node_.param<std::string>(
"robot_state_name", robot_state_name,
"unique_robot_hw");
56 robot_ = robot->getHandle(robot_state_name).getState();
60 ROS_ERROR_STREAM(
"Could not find robot state: " << robot_state_name <<
" Not loading the controller. " <<
67 if (!node_.getParam(
"joint", joint_name_))
69 ROS_ERROR(
"No joint given (namespace: %s)", node_.getNamespace().c_str());
80 has_j2 = is_joint_0();
83 get_joints_states_1_2();
86 ROS_ERROR(
"SrhEffortJointController could not find the first joint relevant to \"%s\"\n", joint_name_.c_str());
91 ROS_ERROR(
"SrhEffortJointController could not find the second joint relevant to \"%s\"\n", joint_name_.c_str());
97 joint_state_ = robot_->getJointState(joint_name_);
100 ROS_ERROR(
"SrhEffortJointController could not find joint named \"%s\"\n", joint_name_.c_str());
108 get_min_max(robot_->robot_model_, joint_name_);
110 serve_set_gains_ = node_.advertiseService(
"set_gains", &SrhEffortJointController::setGains,
this);
111 serve_reset_gains_ = node_.advertiseService(
"reset_gains", &SrhEffortJointController::resetGains,
this);
115 <<
" joint_state: " << joint_state_);
121 void SrhEffortJointController::starting(
const ros::Time &time)
127 bool SrhEffortJointController::setGains(sr_robot_msgs::SetEffortControllerGains::Request &req,
128 sr_robot_msgs::SetEffortControllerGains::Response &resp)
130 max_force_demand = req.max_force;
131 friction_deadband = req.friction_deadband;
134 node_.setParam(
"max_force", max_force_demand);
135 node_.setParam(
"friction_deadband", friction_deadband);
140 bool SrhEffortJointController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
148 "Reseting controller gains: " << joint_state_->joint_->name <<
" and " << joint_state_2->joint_->name);
150 ROS_WARN_STREAM(
"Reseting controller gains: " << joint_state_->joint_->name);
155 void SrhEffortJointController::getGains(
double &p,
double &i,
double &d,
double &i_max,
double &i_min)
161 if (!has_j2 && !joint_state_->calibrated_)
178 double commanded_effort = command_;
181 commanded_effort =
min(commanded_effort, (max_force_demand * max_force_factor_));
182 commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
187 commanded_effort += friction_compensator->friction_compensation(
188 joint_state_->position_ + joint_state_2->position_, joint_state_->velocity_ + joint_state_2->velocity_,
189 static_cast<int>(commanded_effort), friction_deadband);
193 commanded_effort += friction_compensator->friction_compensation(joint_state_->position_, joint_state_->velocity_,
194 static_cast<int>(commanded_effort),
198 joint_state_->commanded_effort_ = commanded_effort;
200 if (loop_count_ % 10 == 0)
202 if (controller_state_publisher_ && controller_state_publisher_->trylock())
204 controller_state_publisher_->msg_.header.stamp = time;
205 controller_state_publisher_->msg_.set_point = command_;
206 controller_state_publisher_->msg_.process_value = joint_state_->effort_;
208 controller_state_publisher_->msg_.process_value_dot = -1.0;
209 controller_state_publisher_->msg_.error = commanded_effort - joint_state_->effort_;
210 controller_state_publisher_->msg_.time_step = period.
toSec();
211 controller_state_publisher_->msg_.command = commanded_effort;
214 getGains(controller_state_publisher_->msg_.p,
215 controller_state_publisher_->msg_.i,
216 controller_state_publisher_->msg_.d,
217 controller_state_publisher_->msg_.i_clamp,
219 controller_state_publisher_->unlockAndPublish();
225 double SrhEffortJointController::clamp_command(
double cmd)
227 return SrController::clamp_command(cmd, eff_min_, eff_max_);
230 void SrhEffortJointController::read_parameters()
232 node_.param<
double>(
"max_force", max_force_demand, 1023.0);
233 node_.param<
int>(
"friction_deadband", friction_deadband, 5);
236 void SrhEffortJointController::setCommandCB(
const std_msgs::Float64ConstPtr &msg)
238 command_ = msg->data;
virtual const char * what() const
Compute an effort demand from the effort error. As the effort PID loop is running on the motor boards...
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
#define ROS_ERROR_STREAM(args)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)