SMACC2
st_navigate_waypoint_1.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
39using namespace sm_autoware_avp::clients;
40
45
47
48// STATE DECLARATION
49struct StNavigateWaypoint1 : smacc2::SmaccState<StNavigateWaypoint1, SmAutowareAvp>
50{
51 using SmaccState::SmaccState;
52
53 // TRANSITION TABLE
54 typedef boost::mpl::list<
55
56 // smacc2::EvCbSuccess<CbNavigateGlobalPosition, OrAutowareAuto>, StNavigateWaypoint2, SUCCESS>,
59
60 >
62
63 // STATE FUNCTIONS
64 static void staticConfigure()
65 {
66 geometry_msgs::msg::PoseStamped goal;
67
68 goal.header.frame_id = "map";
69 goal.pose.position.x = -45.253597259521484;
70 goal.pose.position.y = 93.64368438720703;
71 goal.pose.position.z = 0;
72
73 goal.pose.orientation.z = 0.34841036522579555;
74 goal.pose.orientation.w = 0.9373421026515494;
75
76 configure_orthogonal<OrAutowareAuto, CbNavigateGlobalPosition>(goal);
77 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5);
78 }
79
80 void runtimeConfigure() { RCLCPP_INFO(getLogger(), "Entering StNavigateWaypoint1"); }
81
82 void onEntry() { RCLCPP_INFO(getLogger(), "On Entry!"); }
83
84 void onExit() { RCLCPP_INFO(getLogger(), "On Exit!"); }
85};
86} // namespace sm_autoware_avp
rclcpp::Logger getLogger()
Definition: smacc_state.hpp:36
boost::mpl::list< Transition< EvGoalReached< ClAutoware, OrAutowareAuto >, StFirstPause, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StNavigateWaypoint1, REPLAN > > reactions