-
Notifications
You must be signed in to change notification settings - Fork 28
/
patrol_action_node.cpp
104 lines (80 loc) · 2.66 KB
/
patrol_action_node.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
// Copyright 2019 Intelligent Robotics Lab
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <memory>
#include "geometry_msgs/msg/twist.hpp"
#include "plansys2_executor/ActionExecutorClient.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_action/rclcpp_action.hpp"
#include "lifecycle_msgs/msg/state.hpp"
using namespace std::chrono_literals;
class Patrol : public plansys2::ActionExecutorClient
{
public:
Patrol()
: plansys2::ActionExecutorClient("patrol", 1s)
{
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_activate(const rclcpp_lifecycle::State & previous_state)
{
progress_ = 0.0;
cmd_vel_pub_ = this->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
cmd_vel_pub_->on_activate();
return ActionExecutorClient::on_activate(previous_state);
}
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
on_deactivate(const rclcpp_lifecycle::State & previous_state)
{
cmd_vel_pub_->on_deactivate();
return ActionExecutorClient::on_deactivate(previous_state);
}
private:
void do_work()
{
if (progress_ < 1.0) {
progress_ += 0.1;
send_feedback(progress_, "Patrol running");
geometry_msgs::msg::Twist cmd;
cmd.linear.x = 0.0;
cmd.linear.y = 0.0;
cmd.linear.z = 0.0;
cmd.angular.x = 0.0;
cmd.angular.y = 0.0;
cmd.angular.z = 0.5;
cmd_vel_pub_->publish(cmd);
} else {
geometry_msgs::msg::Twist cmd;
cmd.linear.x = 0.0;
cmd.linear.y = 0.0;
cmd.linear.z = 0.0;
cmd.angular.x = 0.0;
cmd.angular.y = 0.0;
cmd.angular.z = 0.0;
cmd_vel_pub_->publish(cmd);
finish(true, 1.0, "Patrol completed");
}
}
float progress_;
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub_;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<Patrol>();
node->set_parameter(rclcpp::Parameter("action_name", "patrol"));
node->trigger_transition(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
rclcpp::spin(node->get_node_base_interface());
rclcpp::shutdown();
return 0;
}