36 #include <std_msgs/Float64.h> 46 SrhMuscleJointPositionController::SrhMuscleJointPositionController()
47 : position_deadband(0.015), command_acc_(0)
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. " <<
97 ROS_ERROR(
"SrhMuscleJointPositionController could not find the first joint relevant to \"%s\"\n",
103 ROS_ERROR(
"SrhMuscleJointPositionController could not find the second joint relevant to \"%s\"\n",
113 ROS_ERROR(
"SrhMuscleJointPositionController could not find joint named \"%s\"\n",
joint_name_.c_str());
144 sr_robot_msgs::SetPidGains::Response &resp)
146 ROS_INFO_STREAM(
"Setting new PID parameters. P:" << req.p <<
" / I:" << req.i <<
147 " / D:" << req.d <<
" / IClamp:" << req.i_clamp <<
", max force: " << req.max_force <<
148 ", friction deadband: " << req.friction_deadband <<
" pos deadband: " << req.deadband);
222 double pressure_0_tmp = fmod(
joint_state_->effort_, 0x10000);
223 double pressure_1_tmp = (fmod(
joint_state_->effort_, 0x100000000) - pressure_0_tmp) / 0x10000;
224 uint16_t pressure_0 =
static_cast<uint16_t
> (pressure_0_tmp + 0.5);
225 uint16_t pressure_1 =
static_cast<uint16_t
> (pressure_1_tmp + 0.5);
232 double error_position = 0.0;
248 error_position = 0.0;
276 static_cast<int>(commanded_effort),
320 uint16_t valve_tmp[2];
321 for (
int i = 0; i < 2; ++i)
335 valve_tmp[i] = -valve[i] + 8;
339 valve_tmp[i] = valve[i];
346 joint_state_->commanded_effort_ =
static_cast<double> (valve_tmp[0]) + static_cast<double> (valve_tmp[1] << 4);
void get_min_max(urdf::Model model, std::string joint_name)
virtual const char * what() const
ros_ethercat_model::JointState * joint_state_
double position_deadband
the position deadband value used in the hysteresis_deadband
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We're using an hysteresis deadband.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
ros_ethercat_model::JointState * joint_state_2
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_
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::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
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)
virtual void starting(const ros::Time &time)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMusclePositionControllerState > > controller_state_publisher_
publish our joint controller state
double max_force_demand
clamps the force demand to this value
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
void get_joints_states_1_2()
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
ros::ServiceServer serve_set_gains_
int command_acc_
Command accumulator, time to keep the valves open/shut, sign gives the direction. ...
#define ROS_ERROR_STREAM(args)
void read_parameters()
read all the controller settings from the parameter server
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
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_