cartesian_trajectory.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2021 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 
31 #include <cartesian_control_msgs/CartesianTrajectory.h>
32 #include <vector>
33 
35 {
46 {
47 public:
48  CartesianTrajectory() = default;
49 
57  CartesianTrajectory(const cartesian_control_msgs::CartesianTrajectory& ros_trajectory);
58 
59  virtual ~CartesianTrajectory(){};
60 
70  bool init(const cartesian_control_msgs::CartesianTrajectory& ros_trajectory);
71 
91  void sample(const CartesianTrajectorySegment::Time& time, CartesianState& state);
92 
93 private:
94  std::vector<CartesianTrajectorySegment> trajectory_data_;
95 };
96 
97 } // namespace ros_controllers_cartesian
ros_controllers_cartesian
Definition: cartesian_state.h:29
cartesian_trajectory_segment.h
ros_controllers_cartesian::CartesianTrajectory::init
bool init(const cartesian_control_msgs::CartesianTrajectory &ros_trajectory)
Initialize from ROS message.
Definition: cartesian_trajectory.cpp:45
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
cartesian_state.h
ros_controllers_cartesian::CartesianTrajectory
A class for Cartesian trajectory representation and interpolation.
Definition: cartesian_trajectory.h:45
ros_controllers_cartesian::CartesianTrajectory::sample
void sample(const CartesianTrajectorySegment::Time &time, CartesianState &state)
Sample a trajectory at a specified time.
Definition: cartesian_trajectory.cpp:32
ros_controllers_cartesian::CartesianTrajectory::~CartesianTrajectory
virtual ~CartesianTrajectory()
Definition: cartesian_trajectory.h:59
ros_controllers_cartesian::CartesianTrajectory::trajectory_data_
std::vector< CartesianTrajectorySegment > trajectory_data_
Definition: cartesian_trajectory.h:94
ros_controllers_cartesian::CartesianTrajectorySegment::Time
QuinticSplineSegment::Time Time
Relative time in seconds.
Definition: cartesian_trajectory_segment.h:69
ros_controllers_cartesian::CartesianTrajectory::CartesianTrajectory
CartesianTrajectory()=default


cartesian_trajectory_interpolation
Author(s):
autogenerated on Tue Oct 15 2024 02:09:14