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#pragma once
21
24
25#include <ament_index_cpp/get_package_share_directory.hpp>
26
32
34{
35using namespace cl_nav2z;
36using namespace std::chrono_literals;
37
38class OrNavigation : public smacc2::Orthogonal<OrNavigation>
39{
40public:
41 void onInitialize() override
42 {
43 auto movebaseClient = this->createClient<ClNav2Z>();
44
45 // create pose component
46 movebaseClient->createComponent<cl_nav2z::Pose>();
47
48 // create planner switcher
49 movebaseClient->createComponent<PlannerSwitcher>();
50
51 // create goal checker switcher
52 movebaseClient->createComponent<cl_nav2z::GoalCheckerSwitcher>();
53
54 // create odom tracker
55 movebaseClient->createComponent<cl_nav2z::odom_tracker::OdomTracker>();
56
57 // create odom tracker
58 movebaseClient->createComponent<cl_nav2z::CpSlamToolbox>();
59
60 // create waypoints navigator component
61 auto waypointsNavigator = movebaseClient->createComponent<WaypointNavigator>();
62 loadWaypointsFromYaml(waypointsNavigator);
63
64 // change this to skip some points of the yaml file, default = 0
65 waypointsNavigator->currentWaypoint_ = 0;
66 }
67
68 void loadWaypointsFromYaml(WaypointNavigator * waypointsNavigator)
69 {
70 // if it is the first time and the waypoints navigator is not configured
71 std::string planfilepath;
72
73 RCLCPP_INFO_STREAM(getLogger(), "Reasing parameter file from node: " << getNode()->get_name());
74 getNode()->declare_parameter<std::string>("waypoints_plan", "");
75 if (getNode()->get_parameter("waypoints_plan", planfilepath))
76 {
77 std::string package_share_directory =
78 ament_index_cpp::get_package_share_directory("sm_dance_bot_strikes_back");
79 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
80 waypointsNavigator->loadWayPointsFromFile(planfilepath);
81 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
82 }
83 else
84 {
85 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
86 }
87 }
88};
89} // namespace sm_dance_bot_strikes_back
void loadWayPointsFromFile(std::string filepath)
void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)
rclcpp::Node::SharedPtr getNode()
Definition: orthogonal.cpp:47