joint_handle.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2015, Fetch Robotics Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Fetch Robotics Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL FETCH ROBOTICS INC. BE LIABLE FOR ANY
21  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
26  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 // Author: Michael Ferguson
30 
31 #ifndef ROBOT_CONTROLLERS_INTERFACE_JOINT_HANDLE_H
32 #define ROBOT_CONTROLLERS_INTERFACE_JOINT_HANDLE_H
33 
35 
36 namespace robot_controllers
37 {
38 
43 class JointHandle : public Handle
44 {
45 public:
47  {
48  }
49 
51  virtual ~JointHandle()
52  {
53  }
54 
61  virtual void setPosition(double position, double velocity, double effort) = 0;
62 
68  virtual void setVelocity(double velocity, double effort) = 0;
69 
74  virtual void setEffort(double effort) = 0;
75 
77  virtual double getPosition() = 0;
78 
80  virtual double getVelocity() = 0;
81 
83  virtual double getEffort() = 0;
84 
86  virtual bool isContinuous() = 0;
87 
89  virtual double getPositionMin() = 0;
90 
92  virtual double getPositionMax() = 0;
93 
95  virtual double getVelocityMax() = 0;
96 
98  virtual double getEffortMax() = 0;
99 
101  virtual std::string getName() = 0;
102 
104  virtual void reset() = 0;
105 
106 private:
107  // No copy
108  JointHandle(const JointHandle&);
110 };
111 
113 
114 } // namespace robot_controllers
115 
116 #endif // ROBOT_CONTROLLERS_INTERFACE_JOINT_HANDLE_H
virtual double getPositionMin()=0
Get the minimum valid position command.
virtual double getEffortMax()=0
Get the maximum effort command.
virtual bool isContinuous()=0
Is this joint continuous (has no position limits).
virtual ~JointHandle()
Ensure proper cleanup with virtual destructor.
Definition: joint_handle.h:51
virtual void reset()=0
Reset the command.
virtual double getVelocity()=0
Get the velocity of the joint in rad/sec or meters/sec.
Base class for a handle.
Definition: handle.h:43
virtual void setVelocity(double velocity, double effort)=0
Set a velocity command for this joint.
virtual void setPosition(double position, double velocity, double effort)=0
Set a position command for this joint.
boost::shared_ptr< JointHandle > JointHandlePtr
Definition: joint_handle.h:112
Base class for a joint handle. This will be implemented for each type of robot.
Definition: joint_handle.h:43
virtual double getVelocityMax()=0
Get the maximum velocity command.
virtual double getPositionMax()=0
Get the maximum valid position command.
virtual std::string getName()=0
Get the name of this joint.
virtual double getPosition()=0
Get the position of the joint in radians or meters.
virtual void setEffort(double effort)=0
Set an effort command for this joint.
JointHandle & operator=(const JointHandle &)
virtual double getEffort()=0
Get applied effort of a joint in Nm or N.


robot_controllers_interface
Author(s): Michael Ferguson
autogenerated on Sun Sep 27 2020 03:22:36