cartesian_trajectory_segment.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 
32 
34 {
42 
64 {
65 public:
70 
72 
82 
83  CartesianTrajectorySegment() = delete;
84 
86 
110  CartesianTrajectorySegment(const Time& start_time, const CartesianState& start_state, const Time& end_time,
111  const CartesianState& end_state);
112 
125  void sample(const Time& time, CartesianState& state) const;
126 
127 private:
128 };
129 
138 std::ostream& operator<<(std::ostream& os, const CartesianTrajectorySegment::SplineState& state);
139 
162 CartesianTrajectorySegment::SplineState convert(const CartesianState& state);
163 
176 CartesianState convert(const CartesianTrajectorySegment::SplineState& state);
177 
178 } // namespace ros_controllers_cartesian
ros_controllers_cartesian::Time
CartesianTrajectorySegment::Time Time
Definition: cartesian_trajectory_segment.cpp:38
ros_controllers_cartesian
Definition: cartesian_state.h:29
ros_controllers_cartesian::operator<<
std::ostream & operator<<(std::ostream &os, const CartesianTrajectorySegment::SplineState &state)
Stream operator for testing and debugging.
Definition: cartesian_trajectory_segment.cpp:180
pos_vel_acc_state.h
ros_controllers_cartesian::CartesianTrajectorySegment::~CartesianTrajectorySegment
virtual ~CartesianTrajectorySegment()
Definition: cartesian_trajectory_segment.h:85
ros_controllers_cartesian::CartesianTrajectorySegment::CartesianTrajectorySegment
CartesianTrajectorySegment()=delete
ros_controllers_cartesian::CartesianState
Cartesian state with pose, velocity and acceleration.
Definition: cartesian_state.h:38
cartesian_state.h
ros_controllers_cartesian::convert
CartesianTrajectorySegment::SplineState convert(const CartesianState &state)
Convert a CartesianState into a ros_controllers_cartesian::SplineState.
Definition: cartesian_trajectory_segment.cpp:67
ros_controllers_cartesian::CartesianTrajectorySegment::sample
void sample(const Time &time, CartesianState &state) const
Sample the CartesianState at the given time.
Definition: cartesian_trajectory_segment.cpp:45
quintic_spline_segment.h
ros_controllers_cartesian::CartesianTrajectorySegment
Cartesian segment between two trajectory waypoints.
Definition: cartesian_trajectory_segment.h:63
trajectory_interface::PosVelAccState
trajectory_interface::QuinticSplineSegment::Time
Scalar Time
trajectory_interface::QuinticSplineSegment::State
PosVelAccState< Scalar > State
ros_controllers_cartesian::CartesianTrajectorySegment::SplineState
QuinticSplineSegment::State SplineState
State of a 7-dimensional Spline.
Definition: cartesian_trajectory_segment.h:81
trajectory_interface::QuinticSplineSegment


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