SMACC2
st_setup_initial_location_estimation.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 <tf2_geometry_msgs/tf2_geometry_msgs.h>
25#include "rclcpp/rclcpp.hpp"
26#include "smacc2/smacc.hpp"
27
28// LOCAL CLIENTS
30
31// ORTHOGONAL
33
34// CLIENT BEHAVIORS
38
39#include "ros_timer_client/client_behaviors/cb_timer_countdown_once.hpp"
40
41namespace sm_autoware_avp
42{
43// SMACC2 clases
48
49using namespace smacc2::client_behaviors;
51using namespace cl_ros_timer;
52
53//--------------------------------------------------------------------------------
54// STATE DECLARATION
56: smacc2::SmaccState<StSetupInitialLocationEstimation, SmAutowareAvp>
57{
58 using SmaccState::SmaccState;
59
60 // TRANSITION TABLE
61 typedef boost::mpl::list<
62 //Transition<smacc2::EvCbSuccess<CbWaitLocalizationMessage, OrAutowareAuto>, StNavigateWaypoint1, SUCCESS>
65 >
67
68 // STATE FUNCTIONS
69 static void staticConfigure()
70 {
71 geometry_msgs::msg::PoseWithCovarianceStamped initialLocationEstimation;
72
73 initialLocationEstimation.pose.pose.position.x = -61.46;
74 initialLocationEstimation.pose.pose.position.y = -41.25;
75 initialLocationEstimation.pose.pose.position.z = 0;
76
77 initialLocationEstimation.pose.pose.orientation.x = 0;
78 initialLocationEstimation.pose.pose.orientation.y = 0;
79 initialLocationEstimation.pose.pose.orientation.z = -0.9851278757214282;
80 initialLocationEstimation.pose.pose.orientation.w = 0.171822782181485;
81
82 initialLocationEstimation.pose.covariance = {
83 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0,
84 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
85 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891945200942};
86
87 configure_orthogonal<OrAutowareAuto, CbSetupInitialPoseEstimation>(initialLocationEstimation);
88 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5);
89
90 }
91
92 void runtimeConfigure() { RCLCPP_INFO(getLogger(), "Entering StNavigateWaypoint1"); }
93
94 void onEntry() { RCLCPP_INFO(getLogger(), "On Entry!"); }
95
96 void onExit() { RCLCPP_INFO(getLogger(), "On Exit!"); }
97};
98} // namespace sm_autoware_avp
rclcpp::Logger getLogger()
Definition: smacc_state.hpp:36
boost::mpl::list< Transition< sm_autoware_avp::clients::EvAutoLocalized< sm_autoware_avp::clients::ClAutoware, OrAutowareAuto >, StNavigateWaypoint1, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StSetupInitialLocationEstimation, ABORT > > reactions