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#pragma once
16
18
19// clients
21
22// components
29
30#include <ament_index_cpp/get_package_share_directory.hpp>
31
33{
34using namespace cl_nav2z;
35
36class OrNavigation : public smacc2::Orthogonal<OrNavigation>
37{
38public:
39 void onInitialize() override
40 {
41 auto roslaunchClient =this->createClient<smacc2::client_bases::ClRosLaunch>("sm_aws_warehouse_navigation", "navigation_launch.py");
42
43 auto movebaseClient = this->createClient<cl_nav2z::ClNav2Z>();
44
45 // create pose component
46 movebaseClient->createComponent<cl_nav2z::Pose>(StandardReferenceFrames::Map);
47
48 // create planner switcher
49 movebaseClient->createComponent<cl_nav2z::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 movebaseClient->createComponent<cl_nav2z::Amcl>();
58
59 // create waypoints navigator component
60 // auto waypointsNavigator = movebaseClient->createComponent<cl_nav2z::WaypointNavigator>();
61 // loadWaypointsFromYaml(waypointsNavigator);
62
63 // // change this to skip some points of the yaml file, default = 0
64 // waypointsNavigator->currentWaypoint_ = 0;
65 }
66
67 void loadWaypointsFromYaml(WaypointNavigator * waypointsNavigator)
68 {
69 // if it is the first time and the waypoints navigator is not configured
70 std::string planfilepath;
71 getNode()->declare_parameter("waypoints_plan_2", planfilepath);
72 if (getNode()->get_parameter("waypoints_plan_2", planfilepath))
73 {
74 std::string package_share_directory =
75 ament_index_cpp::get_package_share_directory("sm_aws_warehouse_navigation");
76 boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory);
77
78 waypointsNavigator->loadWayPointsFromFile2(planfilepath);
79 RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str());
80 }
81 else
82 {
83 RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE");
84 exit(0);
85 }
86 }
87};
88} // namespace sm_aws_warehouse_navigation
void loadWayPointsFromFile2(std::string filepath)
void loadWaypointsFromYaml(WaypointNavigator *waypointsNavigator)
rclcpp::Node::SharedPtr getNode()
Definition: orthogonal.cpp:47