joint_position_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  * Copyright (c) 2012, hiDOF, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #pragma once
37 
38 
62 #include <control_msgs/JointControllerState.h>
63 #include <control_msgs/JointControllerState.h>
64 #include <control_toolbox/pid.h>
67 #include <memory>
70 #include <ros/node_handle.h>
71 #include <std_msgs/Float64.h>
72 #include <urdf/model.h>
73 
74 namespace effort_controllers
75 {
76 
77 class JointPositionController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
78 {
79 public:
80 
84  struct Commands
85  {
86  double position_; // Last commanded position
87  double velocity_; // Last commanded velocity
88  bool has_velocity_; // false if no velocity command has been specified
89  };
90 
93 
108 
114  void setCommand(double pos_target);
115 
123  void setCommand(double pos_target, double vel_target);
124 
130  void starting(const ros::Time& time);
131 
135  void update(const ros::Time& time, const ros::Duration& period);
136 
140  void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
141 
145  void getGains(double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup);
146 
150  void printDebug();
151 
155  void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup = false);
156 
160  std::string getJointName();
161 
166  double getPosition();
167 
169  urdf::JointConstSharedPtr joint_urdf_;
171  Commands command_struct_; // pre-allocated memory that is re-used to set the realtime buffer
172 
173 private:
177  std::unique_ptr<
179  control_msgs::JointControllerState> > controller_state_publisher_ ;
180 
182 
186  void setCommandCB(const std_msgs::Float64ConstPtr& msg);
187 
193  void enforceJointLimits(double &command);
194 
195 };
196 
197 } // namespace
effort_controllers::JointPositionController::setGains
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup=false)
Set the PID parameters.
Definition: joint_position_controller.cpp:131
realtime_tools::RealtimeBuffer
realtime_publisher.h
node_handle.h
effort_controllers::JointPositionController::Commands::has_velocity_
bool has_velocity_
Definition: joint_position_controller.h:88
effort_controllers::JointPositionController::JointPositionController
JointPositionController()
Definition: joint_position_controller.cpp:81
effort_controllers::JointPositionController::getGains
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.
Definition: joint_position_controller.cpp:141
effort_controllers::JointPositionController::sub_command_
ros::Subscriber sub_command_
Definition: joint_position_controller.h:181
realtime_buffer.h
effort_controllers
Definition: joint_effort_controller.h:42
effort_controllers::JointPositionController::loop_count_
int loop_count_
Definition: joint_position_controller.h:174
effort_controllers::JointPositionController::init
bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
Definition: joint_position_controller.cpp:90
controller_interface::Controller
effort_controllers::JointPositionController::starting
void starting(const ros::Time &time)
This is called from within the realtime thread just before the first call to update.
Definition: joint_position_controller.cpp:184
effort_controllers::JointPositionController::printDebug
void printDebug()
Print debug info to console.
Definition: joint_position_controller.cpp:147
realtime_tools::RealtimePublisher
effort_controllers::JointPositionController::Commands::position_
double position_
Definition: joint_position_controller.h:86
effort_controllers::JointPositionController::Commands::velocity_
double velocity_
Definition: joint_position_controller.h:87
controller.h
joint_command_interface.h
effort_controllers::JointPositionController::pid_controller_
control_toolbox::Pid pid_controller_
Definition: joint_position_controller.h:175
model.h
effort_controllers::JointPositionController::update
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
Definition: joint_position_controller.cpp:199
effort_controllers::JointPositionController::command_struct_
Commands command_struct_
Definition: joint_position_controller.h:171
hardware_interface::EffortJointInterface
effort_controllers::JointPositionController::joint_
hardware_interface::JointHandle joint_
Definition: joint_position_controller.h:168
effort_controllers::JointPositionController::controller_state_publisher_
std::unique_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
Definition: joint_position_controller.h:179
effort_controllers::JointPositionController::joint_urdf_
urdf::JointConstSharedPtr joint_urdf_
Definition: joint_position_controller.h:169
effort_controllers::JointPositionController::setCommand
void setCommand(double pos_target)
Give set position of the joint for next update: revolute (angle) and prismatic (position)
Definition: joint_position_controller.cpp:163
effort_controllers::JointPositionController::command_
realtime_tools::RealtimeBuffer< Commands > command_
Definition: joint_position_controller.h:170
hardware_interface::JointHandle
effort_controllers::JointPositionController::getJointName
std::string getJointName()
Get the name of the joint this controller uses.
Definition: joint_position_controller.cpp:152
effort_controllers::JointPositionController::Commands
Store position and velocity command in struct to allow easier realtime buffer usage.
Definition: joint_position_controller.h:84
ros::Time
effort_controllers::JointPositionController::enforceJointLimits
void enforceJointLimits(double &command)
Check that the command is within the hard limits of the joint. Checks for joint type first....
Definition: joint_position_controller.cpp:286
effort_controllers::JointPositionController
Joint Position Controller.
Definition: joint_position_controller.h:77
control_toolbox::Pid
pid.h
effort_controllers::JointPositionController::~JointPositionController
~JointPositionController()
Definition: joint_position_controller.cpp:85
ros::Duration
effort_controllers::JointPositionController::getPosition
double getPosition()
Get the current position of the joint.
Definition: joint_position_controller.cpp:157
effort_controllers::JointPositionController::setCommandCB
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.
Definition: joint_position_controller.cpp:280
ros::NodeHandle
ros::Subscriber


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Fri May 24 2024 02:41:22