.. _program_listing_file__tmp_ws_src_SMACC2_smacc2_sm_reference_library_sm_aws_warehouse_navigation_include_sm_aws_warehouse_navigation_orthogonals_or_navigation.hpp: Program Listing for File or_navigation.hpp ========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/SMACC2/smacc2_sm_reference_library/sm_aws_warehouse_navigation/include/sm_aws_warehouse_navigation/orthogonals/or_navigation.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // 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. #pragma once #include // clients #include // components #include #include #include #include #include #include #include namespace sm_aws_warehouse_navigation { using namespace cl_nav2z; class OrNavigation : public smacc2::Orthogonal { public: void onInitialize() override { auto roslaunchClient =this->createClient("sm_aws_warehouse_navigation", "navigation_launch.py"); auto nav2zClient = this->createClient(); // create pose component nav2zClient->createComponent(StandardReferenceFrames::Map); // create planner switcher nav2zClient->createComponent(); // create goal checker switcher nav2zClient->createComponent(); // create odom tracker nav2zClient->createComponent(); nav2zClient->createComponent(); // create waypoints navigator component // auto waypointsNavigator = nav2zClient->createComponent(); // loadWaypointsFromYaml(waypointsNavigator); // // change this to skip some points of the yaml file, default = 0 // waypointsNavigator->currentWaypoint_ = 0; } void loadWaypointsFromYaml(WaypointNavigator * waypointsNavigator) { // if it is the first time and the waypoints navigator is not configured std::string planfilepath; getNode()->declare_parameter("waypoints_plan_2", planfilepath); if (getNode()->get_parameter("waypoints_plan_2", planfilepath)) { std::string package_share_directory = ament_index_cpp::get_package_share_directory("sm_aws_warehouse_navigation"); boost::replace_all(planfilepath, "$(pkg_share)", package_share_directory); waypointsNavigator->loadWayPointsFromFile2(planfilepath); RCLCPP_INFO(getLogger(), "waypoints plan: %s", planfilepath.c_str()); } else { RCLCPP_ERROR(getLogger(), "waypoints plan file not found: NONE"); exit(0); } } }; } // namespace sm_aws_warehouse_navigation