38 #include <std_msgs/Float64.h> 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. " <<
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());
128 sr_robot_msgs::SetEffortControllerGains::Response &resp)
189 static_cast<int>(commanded_effort),
void get_min_max(urdf::Model model, std::string joint_name)
ros_ethercat_model::JointState * joint_state_
bool setGains(sr_robot_msgs::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp)
double eff_min_
Min and max range of the effort, used to clamp the command.
void read_parameters()
read all the controller settings from the parameter server
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
Compute an effort demand from the effort error. As the effort PID loop is running on the motor boards...
double clamp_command(double cmd)
clamp the command to effort limits
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
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)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
ros_ethercat_model::RobotState * robot_
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const char * what() const noexcept override
bool getParam(const std::string &key, std::string &s) const
int friction_deadband
the deadband for the friction compensation algorithm
virtual void starting(const ros::Time &time)
double min(double a, double b)
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
std::string getJointName()
#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()
const std::string & getNamespace() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
ros::ServiceServer serve_set_gains_
#define ROS_ERROR_STREAM(args)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the effort target from a topic
double max(double a, double b)
void after_init()
call this function at the end of the init function in the inheriting classes.
ros::ServiceServer serve_reset_gains_