44 JointGroupVelocityController::JointGroupVelocityController()
45 : robot_(NULL), loop_count_(0)
73 for (
int i = 0;
i < joint_names.
size(); ++
i)
76 if (name_value.
getType() != XmlRpcValue::TypeString)
78 ROS_ERROR(
"Array of joint names should contain all strings. (namespace: %s)",
85 ROS_ERROR(
"Joint not found: %s. (namespace: %s)",
110 (
node_,
"statearray", 1));
127 std::vector< std::string > joint_names;
130 joint_names.push_back(
joints_[
i]->joint_->name);
159 std::vector<double> compute_command(
n_joints_);
160 std::vector<double> compute_error(
n_joints_);
164 compute_error[
i] = commands[
i] -
joints_[
i]->velocity_;
166 joints_[i]->commanded_effort_ += command;
167 compute_command[i] = command;
176 pr2_controllers_msgs::JointControllerState singlejointcontrollerstate;
177 singlejointcontrollerstate.header.stamp = time;
178 singlejointcontrollerstate.set_point = commands[
i];
179 singlejointcontrollerstate.process_value =
joints_[
i]->velocity_;
180 singlejointcontrollerstate.error = compute_error[
i];
181 singlejointcontrollerstate.time_step = dt_.
toSec();
182 singlejointcontrollerstate.command = compute_command[
i];
186 singlejointcontrollerstate.p,
187 singlejointcontrollerstate.i,
188 singlejointcontrollerstate.d,
189 singlejointcontrollerstate.i_clamp,
207 ROS_ERROR_STREAM(
"Dimension of command (" << msg->data.size() <<
") does not match number of joints (" <<
n_joints_ <<
")! Not executing!");
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< pr2_mechanism_model::JointState * > joints_
std::vector< std::string > getJointName()
virtual void starting()
Issues commands to the joint. Should be called at regular intervals.
void getCommand(std::vector< double > &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
std::vector< control_toolbox::Pid > pid_controllers_
void setCommand(std::vector< double > cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
pr2_mechanism_model::RobotState * robot_
Type const & getType() const
ROSLIB_DECL std::string command(const std::string &cmd)
ros::Subscriber sub_command_
bool getParam(const std::string &key, std::string &s) const
void getGains(control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray > > controller_state_publisher_
JointState * getJointState(const std::string &name)
const std::string & getNamespace() const
#define ROS_ERROR_STREAM(args)
void setCommandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
bool init(pr2_mechanism_model::RobotState *robot, const std::vector< std::string > &joint_names, const control_toolbox::Pid &pid)
~JointGroupVelocityController()