joint_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_VELOCITY_CONTROLLER_H
36 #define JOINT_VELOCITY_CONTROLLER_H
37 
62 #include <ros/node_handle.h>
63 #include <boost/scoped_ptr.hpp>
64 
66 #include "control_toolbox/pid.h"
68 
69 // Services
70 #include <std_msgs/Float64.h>
71 
72 //Realtime publisher
73 #include <pr2_controllers_msgs/JointControllerState.h>
75 
76 namespace controller
77 {
78 
80 {
81 public:
82 
85 
86  bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
88 
94  void setCommand(double cmd);
95 
99  void getCommand(double & cmd);
100 
105  virtual void starting() {
106  command_ = 0.0;
108  }
109  virtual void update();
110 
111  void getGains(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::string getJointName();
117 
118  double command_;
119 private:
125 
127 
128  boost::scoped_ptr<
130  pr2_controllers_msgs::JointControllerState> > controller_state_publisher_ ;
131 
133  void setCommandCB(const std_msgs::Float64ConstPtr& msg);
134 };
135 
136 } // namespace
137 
138 #endif
realtime_publisher.h
node_handle.h
pr2_mechanism_model::JointState
controller::JointVelocityController::getGains
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Definition: joint_velocity_controller.cpp:111
controller::JointVelocityController::setCommandCB
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Definition: joint_velocity_controller.cpp:168
controller::JointVelocityController::starting
virtual void starting()
Issues commands to the joint. Should be called at regular intervals.
Definition: joint_velocity_controller.h:105
controller::JointVelocityController::controller_state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
Definition: joint_velocity_controller.h:130
controller::JointVelocityController::getJointName
std::string getJointName()
Definition: joint_velocity_controller.cpp:116
controller::JointVelocityController::init
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
Definition: joint_velocity_controller.cpp:54
controller::JointVelocityController::update
virtual void update()
Definition: joint_velocity_controller.cpp:133
realtime_tools::RealtimePublisher
controller::JointVelocityController::JointVelocityController
JointVelocityController()
Definition: joint_velocity_controller.cpp:44
controller::JointVelocityController::setGains
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
Definition: joint_velocity_controller.cpp:105
controller.h
controller
pr2_mechanism_model::RobotState
controller::JointVelocityController::command_
double command_
Definition: joint_velocity_controller.h:118
controller::JointVelocityController::joint_state_
pr2_mechanism_model::JointState * joint_state_
Definition: joint_velocity_controller.h:115
controller::JointVelocityController::pid_controller_
control_toolbox::Pid pid_controller_
Definition: joint_velocity_controller.h:122
controller::JointVelocityController::JointVelocityControllerNode
friend class JointVelocityControllerNode
Definition: joint_velocity_controller.h:126
controller::JointVelocityController::loop_count_
int loop_count_
Definition: joint_velocity_controller.h:124
pr2_controller_interface::Controller
pid_gains_setter.h
controller::JointVelocityController
Definition: joint_velocity_controller.h:79
controller::JointVelocityController::last_time_
ros::Time last_time_
Definition: joint_velocity_controller.h:123
ros::Time
controller::JointVelocityController::sub_command_
ros::Subscriber sub_command_
Definition: joint_velocity_controller.h:132
controller::JointVelocityController::getCommand
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
Definition: joint_velocity_controller.cpp:128
controller::JointVelocityController::dt_
ros::Duration dt_
Definition: joint_velocity_controller.h:116
controller::JointVelocityController::node_
ros::NodeHandle node_
Definition: joint_velocity_controller.h:120
controller::JointVelocityController::~JointVelocityController
~JointVelocityController()
Definition: joint_velocity_controller.cpp:49
control_toolbox::Pid
controller::JointVelocityController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: joint_velocity_controller.h:121
pid.h
cmd
string cmd
control_toolbox::Pid::reset
void reset()
ros::Duration
ros::NodeHandle
ros::Subscriber
controller::JointVelocityController::setCommand
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position)
Definition: joint_velocity_controller.cpp:122


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