src
scaled_joint_trajectory_controller.cpp
Go to the documentation of this file.
1
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
2
3
// -- BEGIN LICENSE BLOCK ----------------------------------------------
4
// Copyright 2019 FZI Forschungszentrum Informatik
5
//
6
// Licensed under the Apache License, Version 2.0 (the "License");
7
// you may not use this file except in compliance with the License.
8
// You may obtain a copy of the License at
9
//
10
// http://www.apache.org/licenses/LICENSE-2.0
11
//
12
// Unless required by applicable law or agreed to in writing, software
13
// distributed under the License is distributed on an "AS IS" BASIS,
14
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15
// See the License for the specific language governing permissions and
16
// limitations under the License.
17
// -- END LICENSE BLOCK ------------------------------------------------
18
19
//----------------------------------------------------------------------
26
//----------------------------------------------------------------------
27
28
#include "
ur_controllers/scaled_joint_trajectory_controller.h
"
29
#include "
ur_controllers/scaled_joint_command_interface.h
"
30
31
#include <
pluginlib/class_list_macros.hpp
>
32
#include <
trajectory_interface/quintic_spline_segment.h
>
33
34
namespace
position_controllers
35
{
36
typedef
ur_controllers::ScaledJointTrajectoryController<trajectory_interface::QuinticSplineSegment<double>
,
37
ur_controllers::ScaledPositionJointInterface
>
38
ScaledJointTrajectoryController
;
39
}
40
41
namespace
velocity_controllers
42
{
43
typedef
ur_controllers::ScaledJointTrajectoryController<trajectory_interface::QuinticSplineSegment<double>
,
44
ur_controllers::ScaledVelocityJointInterface
>
45
ScaledJointTrajectoryController
;
46
}
47
48
PLUGINLIB_EXPORT_CLASS
(
position_controllers::ScaledJointTrajectoryController
,
controller_interface::ControllerBase
)
49
PLUGINLIB_EXPORT_CLASS
(
velocity_controllers::ScaledJointTrajectoryController
,
controller_interface::ControllerBase
)
scaled_joint_command_interface.h
ur_controllers::ScaledJointTrajectoryController
Definition:
scaled_joint_trajectory_controller.h:36
velocity_controllers
class_list_macros.hpp
position_controllers::ScaledJointTrajectoryController
ur_controllers::ScaledJointTrajectoryController< trajectory_interface::QuinticSplineSegment< double >, ur_controllers::ScaledPositionJointInterface > ScaledJointTrajectoryController
Definition:
scaled_joint_trajectory_controller.cpp:38
ur_controllers::ScaledVelocityJointInterface
ScaledJointCommandInterface for commanding velocity-based joints.
Definition:
scaled_joint_command_interface.h:117
controller_interface::ControllerBase
scaled_joint_trajectory_controller.h
position_controllers
ur_controllers::ScaledPositionJointInterface
ScaledJointCommandInterface for commanding position-based joints.
Definition:
scaled_joint_command_interface.h:122
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
quintic_spline_segment.h
ur_controllers
Author(s):
autogenerated on Sun Aug 22 2021 02:38:05