SMACC2
or_navigation.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#pragma once
22
25
26#include <ament_index_cpp/get_package_share_directory.hpp>
27
33
35
36
38{
39using namespace std::chrono_literals;
40
41using ::cl_nav2z::Pose;
42using ::cl_nav2z::GoalCheckerSwitcher;
43using ::cl_nav2z::odom_tracker::OdomTracker;
44using ::cl_nav2z::CpSlamToolbox;
45using cl_nav2z::CpSquareShapeBoundary;
46
47class OrNavigation : public smacc2::Orthogonal<OrNavigation>
48{
49public:
50 void onInitialize() override
51 {
52 auto movebaseClient = this->createClient<ClNav2Z>();
53
54 // create pose component
55 movebaseClient->createComponent<Pose>();
56
57 // create planner switcher
58 movebaseClient->createComponent<PlannerSwitcher>();
59
60 // create goal checker switcher
61 movebaseClient->createComponent<GoalCheckerSwitcher>();
62
63 // create odom tracker
64 movebaseClient->createComponent<OdomTracker>();
65
66 // create odom tracker
67 movebaseClient->createComponent<CpSlamToolbox>();
68
69 // create waypoints navigator component
70 auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();
71 loadWaypointsFromYaml(waypointsNavigator);
72
73 // change this to skip some points of the yaml file, default = 0
74 waypointsNavigator->currentWaypoint_ = 0;
75
76 movebaseClient->createComponent<CpSquareShapeBoundary>(2.5);
77 }
78
79 void loadWaypointsFromYaml(WaypointNavigator * waypointsNavigator)
80 {
81 // if it is the first time and the waypoints navigator is not configured
82 std::string planfilepath;
83 getNode()->declare_parameter("waypoints_plan", planfilepath);
84 if (getNode()->get_parameter("waypoints_plan", planfilepath))
85 {
86 std::string package_share_directory =
87 ament_index_cpp::get_package_share_directory("sm_dance_bot_warehouse");
88 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
89 waypointsNavigator->loadWayPointsFromFile(planfilepath);
90 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
91 }
92 else
93 {
94 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
95 }
96 }
97};
98} // namespace sm_dance_bot_warehouse
void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)
rclcpp::Node::SharedPtr getNode()
Definition: orthogonal.cpp:47