cartesian_state_handle.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //----------------------------------------------------------------------
25 //----------------------------------------------------------------------
26 
27 #pragma once
28 
29 #include <geometry_msgs/Accel.h>
30 #include <geometry_msgs/Pose.h>
31 #include <geometry_msgs/Twist.h>
34 
36 {
49 {
50 public:
51  CartesianStateHandle() = default;
52  CartesianStateHandle(const std::string& ref_frame_id, const std::string& frame_id, const geometry_msgs::Pose* pose,
53  const geometry_msgs::Twist* twist, const geometry_msgs::Accel* accel,
54  const geometry_msgs::Accel* jerk)
55  : frame_id_(frame_id), ref_frame_id_(ref_frame_id), pose_(pose), twist_(twist), accel_(accel), jerk_(jerk)
56  {
57  if (!pose)
58  {
59  throw hardware_interface::HardwareInterfaceException("Cannot create Cartesian handle for frame '" + frame_id_ +
60  "'. Pose data pointer is null.");
61  }
62  if (!twist)
63  {
64  throw hardware_interface::HardwareInterfaceException("Cannot create Cartesian handle for frame '" + frame_id_ +
65  "'. Twist data pointer is null.");
66  }
67  if (!accel)
68  {
69  throw hardware_interface::HardwareInterfaceException("Cannot create Cartesian handle for frame '" + frame_id_ +
70  "'. Accel data pointer is null.");
71  }
72  if (!jerk)
73  {
74  throw hardware_interface::HardwareInterfaceException("Cannot create Cartesian handle for frame '" + frame_id_ +
75  "'. Jerk data pointer is null.");
76  }
77  }
78  virtual ~CartesianStateHandle() = default;
79 
80  std::string getName() const
81  {
82  return frame_id_;
83  }
84  geometry_msgs::Pose getPose() const
85  {
86  assert(pose_);
87  return *pose_;
88  }
89  geometry_msgs::Twist getTwist() const
90  {
91  assert(twist_);
92  return *twist_;
93  }
94  geometry_msgs::Accel getAccel() const
95  {
96  assert(accel_);
97  return *accel_;
98  }
99  geometry_msgs::Accel getJerk() const
100  {
101  assert(jerk_);
102  return *jerk_;
103  }
104 
105 private:
106  std::string frame_id_;
107  std::string ref_frame_id_;
108  const geometry_msgs::Pose* pose_;
109  const geometry_msgs::Twist* twist_;
110  const geometry_msgs::Accel* accel_;
111  const geometry_msgs::Accel* jerk_;
112 };
113 
121 {
122 };
123 } // namespace ros_controllers_cartesian
ros_controllers_cartesian::CartesianStateHandle::frame_id_
std::string frame_id_
Definition: cartesian_state_handle.h:106
ros_controllers_cartesian::CartesianStateHandle::twist_
const geometry_msgs::Twist * twist_
Definition: cartesian_state_handle.h:109
ros_controllers_cartesian::CartesianStateHandle::getName
std::string getName() const
Definition: cartesian_state_handle.h:80
ros_controllers_cartesian
Definition: cartesian_command_interface.h:31
ros_controllers_cartesian::CartesianStateHandle
A state handle for Cartesian hardware interfaces.
Definition: cartesian_state_handle.h:48
ros_controllers_cartesian::CartesianStateHandle::jerk_
const geometry_msgs::Accel * jerk_
Definition: cartesian_state_handle.h:111
ros_controllers_cartesian::CartesianStateHandle::accel_
const geometry_msgs::Accel * accel_
Definition: cartesian_state_handle.h:110
hardware_interface.h
ros_controllers_cartesian::CartesianStateHandle::getAccel
geometry_msgs::Accel getAccel() const
Definition: cartesian_state_handle.h:94
hardware_interface::HardwareInterfaceException
ros_controllers_cartesian::CartesianStateHandle::ref_frame_id_
std::string ref_frame_id_
Definition: cartesian_state_handle.h:107
ros_controllers_cartesian::CartesianStateHandle::getPose
geometry_msgs::Pose getPose() const
Definition: cartesian_state_handle.h:84
ros_controllers_cartesian::CartesianStateHandle::pose_
const geometry_msgs::Pose * pose_
Definition: cartesian_state_handle.h:108
ros_controllers_cartesian::CartesianStateHandle::CartesianStateHandle
CartesianStateHandle(const std::string &ref_frame_id, const std::string &frame_id, const geometry_msgs::Pose *pose, const geometry_msgs::Twist *twist, const geometry_msgs::Accel *accel, const geometry_msgs::Accel *jerk)
Definition: cartesian_state_handle.h:52
ros_controllers_cartesian::CartesianStateHandle::CartesianStateHandle
CartesianStateHandle()=default
ros_controllers_cartesian::CartesianStateHandle::~CartesianStateHandle
virtual ~CartesianStateHandle()=default
ros_controllers_cartesian::CartesianStateInterface
A Cartesian state interface for hardware_interface::RobotHW abstractions.
Definition: cartesian_state_handle.h:120
ros_controllers_cartesian::CartesianStateHandle::getTwist
geometry_msgs::Twist getTwist() const
Definition: cartesian_state_handle.h:89
ros_controllers_cartesian::CartesianStateHandle::getJerk
geometry_msgs::Accel getJerk() const
Definition: cartesian_state_handle.h:99
hardware_interface::HardwareResourceManager
hardware_resource_manager.h


cartesian_interface
Author(s):
autogenerated on Tue Oct 15 2024 02:09:12