posvel_command_interface.h
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF INC.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #pragma once
31 
32 
33 #include <cassert>
34 #include <string>
37 
38 namespace hardware_interface
39 {
40 
43 {
44 public:
45  PosVelJointHandle() = default;
46 
52  PosVelJointHandle(const JointStateHandle& js, double* cmd_pos, double* cmd_vel)
53  : JointStateHandle(js), cmd_pos_(cmd_pos), cmd_vel_(cmd_vel)
54  {
55  if (!cmd_pos)
56  {
57  throw HardwareInterfaceException("Cannot create handle '" + js.getName() + "'. Command position pointer is null.");
58  }
59  if (!cmd_vel)
60  {
61  throw HardwareInterfaceException("Cannot create handle '" + js.getName() + "'. Command velocity pointer is null.");
62  }
63  }
64 
65  void setCommand(double cmd_pos, double cmd_vel)
66  {
67  setCommandPosition(cmd_pos);
68  setCommandVelocity(cmd_vel);
69  }
70 
71  void setCommandPosition(double cmd_pos) {assert(cmd_pos_); *cmd_pos_ = cmd_pos;}
72  void setCommandVelocity(double cmd_vel) {assert(cmd_vel_); *cmd_vel_ = cmd_vel;}
73 
74  double getCommandPosition() const {assert(cmd_pos_); return *cmd_pos_;}
75  double getCommandVelocity() const {assert(cmd_vel_); return *cmd_vel_;}
76 
77 private:
78  double* cmd_pos_ = {nullptr};
79  double* cmd_vel_ = {nullptr};
80 };
81 
90 class PosVelJointInterface : public HardwareResourceManager<PosVelJointHandle, ClaimResources> {};
91 
92 }
hardware_interface::PosVelJointHandle::PosVelJointHandle
PosVelJointHandle(const JointStateHandle &js, double *cmd_pos, double *cmd_vel)
Definition: posvel_command_interface.h:52
hardware_interface::PosVelJointHandle::setCommandVelocity
void setCommandVelocity(double cmd_vel)
Definition: posvel_command_interface.h:72
hardware_interface::PosVelJointHandle
A handle used to read and command a single joint.
Definition: posvel_command_interface.h:42
hardware_interface::PosVelJointHandle::setCommand
void setCommand(double cmd_pos, double cmd_vel)
Definition: posvel_command_interface.h:65
hardware_interface
Definition: actuator_command_interface.h:36
hardware_interface::JointStateHandle
A handle used to read the state of a single joint. Currently, position, velocity and effort fields ar...
Definition: joint_state_interface.h:45
hardware_interface::PosVelJointHandle::cmd_vel_
double * cmd_vel_
Definition: posvel_command_interface.h:79
hardware_interface::JointStateHandle::getName
std::string getName() const
Definition: joint_state_interface.h:166
hardware_interface::HardwareInterfaceException
An exception related to a HardwareInterface.
Definition: hardware_interface.h:71
hardware_interface::PosVelJointHandle::PosVelJointHandle
PosVelJointHandle()=default
joint_state_interface.h
hardware_interface::PosVelJointHandle::getCommandVelocity
double getCommandVelocity() const
Definition: posvel_command_interface.h:75
hardware_interface::PosVelJointHandle::getCommandPosition
double getCommandPosition() const
Definition: posvel_command_interface.h:74
hardware_interface::PosVelJointInterface
Hardware interface to support commanding an array of joints.
Definition: posvel_command_interface.h:90
hardware_interface::PosVelJointHandle::cmd_pos_
double * cmd_pos_
Definition: posvel_command_interface.h:78
hardware_interface::PosVelJointHandle::setCommandPosition
void setCommandPosition(double cmd_pos)
Definition: posvel_command_interface.h:71
hardware_interface::HardwareResourceManager
Base class for handling hardware resources.
Definition: hardware_resource_manager.h:79
hardware_resource_manager.h


hardware_interface
Author(s): Wim Meeussen, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Nov 3 2023 02:07:57