SMACC2
st_start_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#include <smacc2/smacc.hpp>
17
18using namespace std::chrono_literals;
19
21{
22// STATE DECLARATION
23struct StStartNavigation : smacc2::SmaccState<StStartNavigation, SmAwsWarehouseNavigation>
24{
25 using SmaccState::SmaccState;
26
27 // TRANSITION TABLE
28 typedef mpl::list<
29
30 Transition<EvCbSuccess<CbWaitNav2Nodes, OrNavigation>, StInitialNavigateForward, SUCCESS>
31 // , Transition<EvActionAborted<ClNav2Z, OrNavigation>, StAcquireSensors, ABORT>
32 //Transition<EvCbSuccess<OrNavigation, CbWaitTransform>, StInitialNavigateForward, SUCCESS> >
33 >
35
36 // STATE FUNCTIONS
37 static void staticConfigure()
38 {
39 configure_orthogonal<OrNavigation, CbRosLaunch>();
40 configure_orthogonal<OrNavigation, CbWaitNav2Nodes>();
41 }
42
44 {
45 // illegal wait workaround
46 // rclcpp::sleep_for(6s);
47
48 // ClNav2Z * navClient;
49 // getOrthogonal<OrNavigation>()->requiresClient(navClient);
50
51 // amcl_ = navClient->getComponent<Amcl>();
52 }
53
54 void onEntry()
55 {
56 //sendInitialPoseEstimation();
57 //auto res = exec("ros2");
58 //RCLCPP_INFO(getLogger(), "launch result: %s", res.c_str());
59 }
60
62 {
63 geometry_msgs::msg::PoseWithCovarianceStamped initialposemsg;
64 // bool useSimTime = getNode()->get_parameter("use_sim_time").as_bool();
65 //getNode()->set_parameter("use_sim_time",true);
66
67 initialposemsg.header.stamp = getNode()->now();
68 initialposemsg.header.frame_id = "map";
69
70 initialposemsg.pose.pose.position.x = 3.415412425994873;
71 initialposemsg.pose.pose.position.y = 2.0;
72 initialposemsg.pose.pose.position.z = 0;
73
74 initialposemsg.pose.pose.orientation.x = 0;
75 initialposemsg.pose.pose.orientation.y = 0;
76 initialposemsg.pose.pose.orientation.z = 1;
77 initialposemsg.pose.pose.orientation.w = 0;
78
79 //z: 0.9999985465626609
80 // w: 0.00170495529732811
81
82 initialposemsg.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.06853891909122467};
86
87 // amcl_->setInitialPose(initialposemsg);
88 }
89
90 void onExit() {}
91};
92} // namespace sm_aws_warehouse_navigation
rclcpp::Node::SharedPtr & getNode()
Definition: smacc_state.hpp:34
mpl::list< Transition< EvCbSuccess< CbWaitNav2Nodes, OrNavigation >, StInitialNavigateForward, SUCCESS > > reactions