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 
175 
176 } // namespace ros_controllers_cartesian
void sample(const Time &time, CartesianState &state) const
Sample the CartesianState at the given time.
Cartesian segment between two trajectory waypoints.
std::ostream & operator<<(std::ostream &os, const CartesianTrajectorySegment::SplineState &state)
Stream operator for testing and debugging.
CartesianTrajectorySegment::SplineState convert(const CartesianState &state)
Convert a CartesianState into a ros_controllers_cartesian::SplineState.
Cartesian state with pose, velocity and acceleration.


cartesian_trajectory_interpolation
Author(s):
autogenerated on Thu Feb 23 2023 03:10:46