include
cob_cartesian_controller
trajectory_interpolator
trajectory_interpolator.h
Go to the documentation of this file.
1
/*
2
* Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*/
16
17
18
#ifndef COB_CARTESIAN_CONTROLLER_TRAJECTORY_INTERPOLATOR_TRAJECTORY_INTERPOLATOR_H
19
#define COB_CARTESIAN_CONTROLLER_TRAJECTORY_INTERPOLATOR_TRAJECTORY_INTERPOLATOR_H
20
21
#include <string>
22
#include <
ros/ros.h
>
23
#include <geometry_msgs/PoseArray.h>
24
#include <
tf/transform_datatypes.h
>
25
26
#include <
cob_cartesian_controller/cartesian_controller_data_types.h
>
27
#include <
cob_cartesian_controller/trajectory_profile_generator/trajectory_profile_generator_builder.h
>
28
29
class
TrajectoryInterpolator
30
{
31
public
:
32
TrajectoryInterpolator
(std::string root_frame,
double
update_rate)
33
:
root_frame_
(
root_frame
)
34
{}
35
36
~TrajectoryInterpolator
()
37
{
38
trajectory_profile_generator_
.reset();
39
}
40
41
bool
linearInterpolation
(geometry_msgs::PoseArray& pose_array,
42
const
cob_cartesian_controller::CartesianActionStruct
as);
43
44
bool
circularInterpolation
(geometry_msgs::PoseArray& pose_array,
45
const
cob_cartesian_controller::CartesianActionStruct
as);
46
47
private
:
48
std::string
root_frame_
;
49
boost::shared_ptr<TrajectoryProfileBase>
trajectory_profile_generator_
;
50
};
51
52
#endif // COB_CARTESIAN_CONTROLLER_TRAJECTORY_INTERPOLATOR_TRAJECTORY_INTERPOLATOR_H
boost::shared_ptr< TrajectoryProfileBase >
TrajectoryInterpolator::root_frame_
std::string root_frame_
Definition:
trajectory_interpolator.h:48
TrajectoryInterpolator
Definition:
trajectory_interpolator.h:29
ros.h
TrajectoryInterpolator::circularInterpolation
bool circularInterpolation(geometry_msgs::PoseArray &pose_array, const cob_cartesian_controller::CartesianActionStruct as)
Definition:
trajectory_interpolator.cpp:88
TrajectoryInterpolator::trajectory_profile_generator_
boost::shared_ptr< TrajectoryProfileBase > trajectory_profile_generator_
Definition:
trajectory_interpolator.h:49
trajectory_profile_generator_builder.h
TrajectoryInterpolator::~TrajectoryInterpolator
~TrajectoryInterpolator()
Definition:
trajectory_interpolator.h:36
root_frame
root_frame
TrajectoryInterpolator::TrajectoryInterpolator
TrajectoryInterpolator(std::string root_frame, double update_rate)
Definition:
trajectory_interpolator.h:32
transform_datatypes.h
cartesian_controller_data_types.h
cob_cartesian_controller::CartesianActionStruct
Definition:
cartesian_controller_data_types.h:55
TrajectoryInterpolator::linearInterpolation
bool linearInterpolation(geometry_msgs::PoseArray &pose_array, const cob_cartesian_controller::CartesianActionStruct as)
Definition:
trajectory_interpolator.cpp:24
cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Mon May 1 2023 02:44:52