-
Notifications
You must be signed in to change notification settings - Fork 337
/
Copy pathcontroller.cpp
125 lines (99 loc) · 2.89 KB
/
controller.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
#include "ur_modern_driver/ros/controller.h"
ROSController::ROSController(URCommander& commander, TrajectoryFollower& follower,
std::vector<std::string>& joint_names, double max_vel_change, std::string tcp_link)
: controller_(this, nh_)
, joint_interface_(joint_names)
, wrench_interface_(tcp_link)
, position_interface_(follower, joint_interface_, joint_names)
, velocity_interface_(commander, joint_interface_, joint_names, max_vel_change)
{
registerInterface(&joint_interface_);
registerInterface(&wrench_interface_);
registerControllereInterface(&position_interface_);
registerControllereInterface(&velocity_interface_);
}
void ROSController::setupConsumer()
{
lastUpdate_ = ros::Time::now();
}
void ROSController::doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
const std::list<hardware_interface::ControllerInfo>& stop_list)
{
LOG_INFO("Switching hardware interface");
if (active_interface_ != nullptr && stop_list.size() > 0)
{
LOG_INFO("Stopping active interface");
active_interface_->stop();
active_interface_ = nullptr;
}
for (auto const& ci : start_list)
{
std::string requested_interface("");
#if defined(UR_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL)
requested_interface = ci.hardware_interface;
#else
if (!ci.claimed_resources.empty())
requested_interface = ci.claimed_resources[0].hardware_interface;
#endif
auto ait = available_interfaces_.find(requested_interface);
if (ait == available_interfaces_.end())
continue;
auto new_interface = ait->second;
LOG_INFO("Starting %s", ci.name.c_str());
active_interface_ = new_interface;
new_interface->start();
return;
}
if(start_list.size() > 0)
LOG_WARN("Failed to start interface!");
}
bool ROSController::write()
{
if (active_interface_ == nullptr)
return true;
return active_interface_->write();
}
void ROSController::reset()
{
if (active_interface_ == nullptr)
return;
active_interface_->reset();
}
void ROSController::read(RTShared& packet)
{
joint_interface_.update(packet);
wrench_interface_.update(packet);
}
bool ROSController::update()
{
auto time = ros::Time::now();
auto diff = time - lastUpdate_;
lastUpdate_ = time;
controller_.update(time, diff, !service_enabled_);
// emergency stop and such should not kill the pipeline
// but still prevent writes
if (!service_enabled_)
{
reset();
return true;
}
// allow the controller to update x times before allowing writes again
if (service_cooldown_ > 0)
{
service_cooldown_ -= 1;
return true;
}
return write();
}
void ROSController::onTimeout()
{
update();
}
void ROSController::onRobotStateChange(RobotState state)
{
bool next = (state == RobotState::Running);
if (next == service_enabled_)
return;
service_enabled_ = next;
service_cooldown_ = 125;
}