src
joint_velocity_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/joint_velocity_example_controller.h
>
4
5
#include <cmath>
6
7
#include <
controller_interface/controller_base.h
>
8
#include <
hardware_interface/hardware_interface.h
>
9
#include <
hardware_interface/joint_command_interface.h
>
10
#include <
pluginlib/class_list_macros.h
>
11
#include <
ros/ros.h
>
12
13
namespace
franka_example_controllers
{
14
15
bool
JointVelocityExampleController::init
(
hardware_interface::RobotHW
* robot_hardware,
16
ros::NodeHandle
& node_handle) {
17
velocity_joint_interface_
= robot_hardware->
get
<
hardware_interface::VelocityJointInterface
>();
18
if
(
velocity_joint_interface_
==
nullptr
) {
19
ROS_ERROR
(
20
"JointVelocityExampleController: Error getting velocity joint interface from hardware!"
);
21
return
false
;
22
}
23
24
std::string
arm_id
;
25
if
(!node_handle.
getParam
(
"arm_id"
,
arm_id
)) {
26
ROS_ERROR
(
"JointVelocityExampleController: Could not get parameter arm_id"
);
27
return
false
;
28
}
29
30
std::vector<std::string>
joint_names
;
31
if
(!node_handle.
getParam
(
"joint_names"
,
joint_names
)) {
32
ROS_ERROR
(
"JointVelocityExampleController: Could not parse joint names"
);
33
}
34
if
(
joint_names
.size() != 7) {
35
ROS_ERROR_STREAM
(
"JointVelocityExampleController: Wrong number of joint names, got "
36
<<
joint_names
.size() <<
" instead of 7 names!"
);
37
return
false
;
38
}
39
velocity_joint_handles_
.resize(7);
40
for
(
size_t
i = 0; i < 7; ++i) {
41
try
{
42
velocity_joint_handles_
[i] =
velocity_joint_interface_
->
getHandle
(
joint_names
[i]);
43
}
catch
(
const
hardware_interface::HardwareInterfaceException
& ex) {
44
ROS_ERROR_STREAM
(
45
"JointVelocityExampleController: Exception getting joint handles: "
<< ex.
what
());
46
return
false
;
47
}
48
}
49
50
auto
state_interface = robot_hardware->
get
<
franka_hw::FrankaStateInterface
>();
51
if
(state_interface ==
nullptr
) {
52
ROS_ERROR
(
"JointVelocityExampleController: Could not get state interface from hardware"
);
53
return
false
;
54
}
55
56
try
{
57
auto
state_handle = state_interface->getHandle(
arm_id
+
"_robot"
);
58
59
std::array<double, 7> q_start{{0, -M_PI_4, 0, -3 * M_PI_4, 0, M_PI_2, M_PI_4}};
60
for
(
size_t
i = 0; i < q_start.size(); i++) {
61
if
(std::abs(state_handle.getRobotState().q_d[i] - q_start[i]) > 0.1) {
62
ROS_ERROR_STREAM
(
63
"JointVelocityExampleController: Robot is not in the expected starting position for "
64
"running this example. Run `roslaunch franka_example_controllers move_to_start.launch "
65
"robot_ip:=<robot-ip> load_gripper:=<has-attached-gripper>` first."
);
66
return
false
;
67
}
68
}
69
}
catch
(
const
hardware_interface::HardwareInterfaceException
& e) {
70
ROS_ERROR_STREAM
(
71
"JointVelocityExampleController: Exception getting state handle: "
<< e.
what
());
72
return
false
;
73
}
74
75
return
true
;
76
}
77
78
void
JointVelocityExampleController::starting
(
const
ros::Time
&
/* time */
) {
79
elapsed_time_
=
ros::Duration
(0.0);
80
}
81
82
void
JointVelocityExampleController::update
(
const
ros::Time
&
/* time */
,
83
const
ros::Duration
& period) {
84
elapsed_time_
+= period;
85
86
ros::Duration
time_max(8.0);
87
double
omega_max = 0.1;
88
double
cycle = std::floor(
89
std::pow(-1.0, (
elapsed_time_
.
toSec
() - std::fmod(
elapsed_time_
.
toSec
(), time_max.
toSec
())) /
90
time_max.
toSec
()));
91
double
omega = cycle * omega_max / 2.0 *
92
(1.0 - std::cos(2.0 * M_PI / time_max.
toSec
() *
elapsed_time_
.
toSec
()));
93
94
for
(
auto
joint_handle :
velocity_joint_handles_
) {
95
joint_handle.setCommand(omega);
96
}
97
}
98
99
void
JointVelocityExampleController::stopping
(
const
ros::Time
&
/*time*/
) {
100
// WARNING: DO NOT SEND ZERO VELOCITIES HERE AS IN CASE OF ABORTING DURING MOTION
101
// A JUMP TO ZERO WILL BE COMMANDED PUTTING HIGH LOADS ON THE ROBOT. LET THE DEFAULT
102
// BUILT-IN STOPPING BEHAVIOR SLOW DOWN THE ROBOT.
103
}
104
105
}
// namespace franka_example_controllers
106
107
PLUGINLIB_EXPORT_CLASS
(
franka_example_controllers::JointVelocityExampleController
,
108
controller_interface::ControllerBase
)
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
HardwareResourceManager< JointHandle, ClaimResources >::getHandle
JointHandle getHandle(const std::string &name)
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::JointVelocityExampleController
Definition:
joint_velocity_example_controller.h:17
hardware_interface.h
franka_example_controllers::JointVelocityExampleController::elapsed_time_
ros::Duration elapsed_time_
Definition:
joint_velocity_example_controller.h:29
class_list_macros.h
franka_example_controllers::JointVelocityExampleController::starting
void starting(const ros::Time &) override
Definition:
joint_velocity_example_controller.cpp:78
controller_interface::ControllerBase
hardware_interface::VelocityJointInterface
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::JointVelocityExampleController::velocity_joint_handles_
std::vector< hardware_interface::JointHandle > velocity_joint_handles_
Definition:
joint_velocity_example_controller.h:28
joint_command_interface.h
hardware_interface::RobotHW
joint_velocity_example_controller.h
controller_base.h
arm_id
std::string arm_id
franka_example_controllers::JointVelocityExampleController::velocity_joint_interface_
hardware_interface::VelocityJointInterface * velocity_joint_interface_
Definition:
joint_velocity_example_controller.h:27
ROS_ERROR
#define ROS_ERROR(...)
franka_example_controllers::JointVelocityExampleController::init
bool init(hardware_interface::RobotHW *robot_hardware, ros::NodeHandle &node_handle) override
Definition:
joint_velocity_example_controller.cpp:15
franka_hw::FrankaStateInterface
hardware_interface::HardwareInterfaceException
ros::Time
franka_example_controllers::JointVelocityExampleController::stopping
void stopping(const ros::Time &) override
Definition:
joint_velocity_example_controller.cpp:99
joint_names
std::array< std::string, 7 > joint_names
franka_example_controllers::JointVelocityExampleController::update
void update(const ros::Time &, const ros::Duration &period) override
Definition:
joint_velocity_example_controller.cpp:82
DurationBase< Duration >::toSec
double toSec() const
ros::Duration
ros::NodeHandle
franka_example_controllers
Author(s): Franka Emika GmbH
autogenerated on Mon Sep 19 2022 02:33:26