SMACC2
st_navigate_waypoint_2.hpp
Go to the documentation of this file.
1// Copyright 2021 MyName/MyCompany Inc.
2// Copyright 2021 RobosoftAI Inc. (template)
3//
4// Licensed under the Apache License, Version 2.0 (the "License");
5// you may not use this file except in compliance with the License.
6// You may obtain a copy of the License at
7//
8// http://www.apache.org/licenses/LICENSE-2.0
9//
10// Unless required by applicable law or agreed to in writing, software
11// distributed under the License is distributed on an "AS IS" BASIS,
12// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13// See the License for the specific language governing permissions and
14// limitations under the License.
15
16/*****************************************************************************************************************
17 *
18 * Authors: Pablo Inigo Blasco, Brett Aldrich
19 *
20 ******************************************************************************************************************/
21
22#pragma once
23
24#include "rclcpp/rclcpp.hpp"
25#include "smacc2/smacc.hpp"
26
27// CLIENTS
28#include "ros_timer_client/cl_ros_timer.hpp"
29#include "ros_timer_client/client_behaviors/cb_timer_countdown_loop.hpp"
30#include "ros_timer_client/client_behaviors/cb_timer_countdown_once.hpp"
31
32// ORTHOGONALS
34
35namespace sm_autoware_avp
36{
37// SMACC2 clases
42
43using namespace sm_autoware_avp::clients;
44
45// STATE DECLARATION
46struct StNavigateWaypoint2 : smacc2::SmaccState<StNavigateWaypoint2, SmAutowareAvp>
47{
48 using SmaccState::SmaccState;
49
50 // TRANSITION TABLE
51 typedef boost::mpl::list<
52
55
56 >
58
59 // STATE FUNCTIONS
60 static void staticConfigure()
61 {
62 geometry_msgs::msg::PoseStamped goal;
63 goal.header.frame_id = "map";
64 goal.pose.position.x = -92.7;
65 goal.pose.position.y = 15.4;
66 goal.pose.position.z = 0;
67
68 goal.pose.orientation.z = -0.6221545523727376;
69 goal.pose.orientation.w = 0.7828944456067359;
70
71 configure_orthogonal<OrAutowareAuto, CbNavigateGlobalPosition>(goal);
72 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(12);
73 }
74
75 void runtimeConfigure() { RCLCPP_INFO(getLogger(), "Entering StNavigateWaypoint2"); }
76
77 void onEntry() { RCLCPP_INFO(getLogger(), "On Entry!"); }
78
79 void onExit() { RCLCPP_INFO(getLogger(), "On Exit!"); }
80};
81} // namespace sm_autoware_avp
rclcpp::Logger getLogger()
Definition: smacc_state.hpp:36
boost::mpl::list< Transition< EvGoalReached< ClAutoware, OrAutowareAuto >, StSecondPause, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StNavigateWaypoint2, REPLAN > > reactions