src
elbow_example_controller.cpp
Go to the documentation of this file.
1
// Copyright (c) 2017 Franka Emika GmbH
2
// Use of this source code is governed by the Apache-2.0 license, see LICENSE
3
#include <
franka_example_controllers/elbow_example_controller.h
>
4
5
#include <cmath>
6
#include <memory>
7
#include <stdexcept>
8
#include <string>
9
10
#include <
controller_interface/controller_base.h
>
11
#include <
franka_hw/franka_cartesian_command_interface.h
>
12
#include <
hardware_interface/hardware_interface.h
>
13
#include <
pluginlib/class_list_macros.h
>
14
#include <
ros/ros.h
>
15
16
namespace
franka_example_controllers
{
17
18
bool
ElbowExampleController::init
(
hardware_interface::RobotHW
* robot_hardware,
19
ros::NodeHandle
& node_handle) {
20
cartesian_pose_interface_
= robot_hardware->
get
<
franka_hw::FrankaPoseCartesianInterface
>();
21
if
(
cartesian_pose_interface_
==
nullptr
) {
22
ROS_ERROR
(
"ElbowExampleController: Could not get Cartesian Pose interface from hardware"
);
23
return
false
;
24
}
25
26
std::string
arm_id
;
27
if
(!node_handle.
getParam
(
"arm_id"
,
arm_id
)) {
28
ROS_ERROR
(
"ElbowExampleController: Could not get parameter arm_id"
);
29
return
false
;
30
}
31
32
try
{
33
cartesian_pose_handle_
= std::make_unique<franka_hw::FrankaCartesianPoseHandle>(
34
cartesian_pose_interface_
->getHandle(
arm_id
+
"_robot"
));
35
}
catch
(
const
hardware_interface::HardwareInterfaceException
& e) {
36
ROS_ERROR_STREAM
(
"ElbowExampleController: Exception getting Cartesian handle: "
<< e.
what
());
37
return
false
;
38
}
39
40
auto
state_interface = robot_hardware->
get
<
franka_hw::FrankaStateInterface
>();
41
if
(state_interface ==
nullptr
) {
42
ROS_ERROR
(
"ElbowExampleController: Could not get state interface from hardware"
);
43
return
false
;
44
}
45
46
try
{
47
auto
state_handle = state_interface->getHandle(
arm_id
+
"_robot"
);
48
49
std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
50
for
(
size_t
i = 0; i < q_start.size(); i++) {
51
if
(std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) {
52
ROS_ERROR_STREAM
(
53
"ElbowExampleController: Robot is not in the expected starting position for "
54
"running this example. Run `roslaunch franka_example_controllers move_to_start.launch "
55
"robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."
);
56
return
false
;
57
}
58
}
59
}
catch
(
const
hardware_interface::HardwareInterfaceException
& e) {
60
ROS_ERROR_STREAM
(
"ElbowExampleController: Exception getting state handle: "
<< e.
what
());
61
return
false
;
62
}
63
64
return
true
;
65
}
66
67
void
ElbowExampleController::starting
(
const
ros::Time
&
/* time */
) {
68
initial_pose_
=
cartesian_pose_handle_
->getRobotState().O_T_EE_d;
69
initial_elbow_
=
cartesian_pose_handle_
->getRobotState().elbow_d;
70
elapsed_time_
=
ros::Duration
(0.0);
71
}
72
73
void
ElbowExampleController::update
(
const
ros::Time
&
/* time */
,
const
ros::Duration
& period) {
74
elapsed_time_
+= period;
75
76
double
angle
= M_PI / 10.0 * (1.0 - std::cos(M_PI / 5.0 *
elapsed_time_
.
toSec
()));
77
auto
elbow =
initial_elbow_
;
78
elbow[0] +=
angle
;
79
80
cartesian_pose_handle_
->setCommand(
initial_pose_
, elbow);
81
}
82
83
}
// namespace franka_example_controllers
84
85
PLUGINLIB_EXPORT_CLASS
(
franka_example_controllers::ElbowExampleController
,
86
controller_interface::ControllerBase
)
franka_example_controllers::ElbowExampleController::starting
void starting(const ros::Time &) override
Definition:
elbow_example_controller.cpp:67
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
hardware_interface::HardwareInterfaceException::what
const char * what() const noexcept override
hardware_interface::InterfaceManager::get
T * get()
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
franka_example_controllers::ElbowExampleController::cartesian_pose_interface_
franka_hw::FrankaPoseCartesianInterface * cartesian_pose_interface_
Definition:
elbow_example_controller.h:28
hardware_interface.h
franka_example_controllers::ElbowExampleController
Definition:
elbow_example_controller.h:19
class_list_macros.h
controller_interface::ControllerBase
franka_example_controllers
Definition:
cartesian_impedance_example_controller.h:23
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
franka_example_controllers::ElbowExampleController::initial_pose_
std::array< double, 16 > initial_pose_
Definition:
elbow_example_controller.h:31
hardware_interface::RobotHW
franka_hw::FrankaPoseCartesianInterface
controller_base.h
arm_id
std::string arm_id
ROS_ERROR
#define ROS_ERROR(...)
franka_hw::FrankaStateInterface
franka_example_controllers::ElbowExampleController::elapsed_time_
ros::Duration elapsed_time_
Definition:
elbow_example_controller.h:30
franka_example_controllers::ElbowExampleController::init
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
Definition:
elbow_example_controller.cpp:18
franka_example_controllers::ElbowExampleController::initial_elbow_
std::array< double, 2 > initial_elbow_
Definition:
elbow_example_controller.h:32
franka_example_controllers::ElbowExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition:
elbow_example_controller.cpp:73
hardware_interface::HardwareInterfaceException
ros::Time
franka_example_controllers::ElbowExampleController::cartesian_pose_handle_
std::unique_ptr< franka_hw::FrankaCartesianPoseHandle > cartesian_pose_handle_
Definition:
elbow_example_controller.h:29
DurationBase< Duration >::toSec
double toSec() const
elbow_example_controller.h
ros::Duration
franka_cartesian_command_interface.h
ros::NodeHandle
franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:26