44 JointVelocityController::JointVelocityController()
45 : joint_state_(NULL), command_(0), robot_(NULL), last_time_(0), loop_count_(0)
64 ROS_ERROR(
"JointVelocityController could not find joint named \"%s\"\n",
80 std::string joint_name;
87 ROS_ERROR(
"Could not find joint \"%s\" (namespace: %s)",
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
pr2_mechanism_model::JointState * joint_state_
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber sub_command_
boost::shared_ptr< const urdf::Joint > joint_
~JointVelocityController()
pr2_mechanism_model::RobotState * robot_
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
ROSLIB_DECL std::string command(const std::string &cmd)
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
const std::string & getNamespace() const
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
JointState * getJointState(const std::string &name)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
bool getParam(const std::string &key, std::string &s) const
control_toolbox::Pid pid_controller_
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
std::string getJointName()
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)