joint_group_velocity_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef JOINT_GROUP_VELOCITY_CONTROLLER_H
36 #define JOINT_GROUP_VELOCITY_CONTROLLER_H
37 
62 #include <ros/node_handle.h>
63 #include <boost/scoped_ptr.hpp>
64 #include <boost/thread/condition.hpp>
65 
67 #include "control_toolbox/pid.h"
69 
70 // Services
71 #include <std_msgs/Float64.h>
72 #include <std_msgs/Float64MultiArray.h>
73 
74 //Realtime publisher
75 #include <pr2_controllers_msgs/JointControllerState.h>
76 #include <pr2_controllers_msgs/JointControllerStateArray.h>
78 
79 namespace controller
80 {
81 
83 {
84 public:
85 
88 
89  bool init(pr2_mechanism_model::RobotState *robot, const std::vector< std::string> &joint_names, const control_toolbox::Pid &pid);
91 
97  void setCommand(std::vector<double> cmd);
98 
102  void getCommand(std::vector<double> & cmd);
103 
108  virtual void starting();
109  virtual void update();
110 
111  void getGains(control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min);
112  //void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
113 
114  std::vector< std::string > getJointName();
115  unsigned int n_joints_;
116 
117 private:
120  std::vector<control_toolbox::Pid> pid_controllers_;
121  std::vector<pr2_mechanism_model::JointState*> joints_;
124 
128 
129  boost::scoped_ptr<
131  pr2_controllers_msgs::JointControllerStateArray> > controller_state_publisher_ ;
132 
134  void setCommandCB(const std_msgs::Float64MultiArrayConstPtr& msg);
135 };
136 
137 } // namespace
138 
139 #endif
realtime_tools::RealtimeBuffer
realtime_publisher.h
node_handle.h
controller::JointGroupVelocityController::last_time_
ros::Time last_time_
Definition: joint_group_velocity_controller.h:122
controller::JointGroupVelocityController::joints_
std::vector< pr2_mechanism_model::JointState * > joints_
Definition: joint_group_velocity_controller.h:121
i
int i
controller::JointGroupVelocityController::n_joints_
unsigned int n_joints_
Definition: joint_group_velocity_controller.h:115
controller::JointGroupVelocityController::pid_controllers_
std::vector< control_toolbox::Pid > pid_controllers_
Definition: joint_group_velocity_controller.h:120
controller::JointGroupVelocityController::init
bool init(pr2_mechanism_model::RobotState *robot, const std::vector< std::string > &joint_names, const control_toolbox::Pid &pid)
controller::JointGroupVelocityController::sub_command_
ros::Subscriber sub_command_
Definition: joint_group_velocity_controller.h:133
controller::JointGroupVelocityController::starting
virtual void starting()
Issues commands to the joint. Should be called at regular intervals.
Definition: joint_group_velocity_controller.cpp:147
controller::JointGroupVelocityController::update
virtual void update()
Definition: joint_group_velocity_controller.cpp:153
controller::JointGroupVelocityController::controller_state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray > > controller_state_publisher_
Definition: joint_group_velocity_controller.h:131
controller::JointGroupVelocityController::setCommand
void setCommand(std::vector< double > cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position)
Definition: joint_group_velocity_controller.cpp:136
realtime_tools::RealtimePublisher
controller::JointGroupVelocityController::commands_buffer_
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
Definition: joint_group_velocity_controller.h:125
controller::JointGroupVelocityController::getJointName
std::vector< std::string > getJointName()
Definition: joint_group_velocity_controller.cpp:125
controller.h
controller
pr2_mechanism_model::RobotState
d
d
controller::JointGroupVelocityController
Definition: joint_group_velocity_controller.h:82
controller::JointGroupVelocityController::JointGroupVelocityController
JointGroupVelocityController()
Definition: joint_group_velocity_controller.cpp:44
controller::JointGroupVelocityController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: joint_group_velocity_controller.h:119
controller::JointGroupVelocityController::~JointGroupVelocityController
~JointGroupVelocityController()
Definition: joint_group_velocity_controller.cpp:49
pr2_controller_interface::Controller
pid_gains_setter.h
ros::Time
control_toolbox::Pid
pid.h
controller::JointGroupVelocityController::loop_count_
int loop_count_
Definition: joint_group_velocity_controller.h:123
controller::JointGroupVelocityController::getGains
void getGains(control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min)
Definition: joint_group_velocity_controller.cpp:120
cmd
string cmd
controller::JointGroupVelocityController::getCommand
void getCommand(std::vector< double > &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
Definition: joint_group_velocity_controller.cpp:142
controller::JointGroupVelocityController::setCommandCB
void setCommandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
Definition: joint_group_velocity_controller.cpp:202
controller::JointGroupVelocityController::node_
ros::NodeHandle node_
Definition: joint_group_velocity_controller.h:118
ros::NodeHandle
ros::Subscriber
controller::JointGroupVelocityController::JointGroupVelocityControllerNode
friend class JointGroupVelocityControllerNode
Definition: joint_group_velocity_controller.h:127


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:22