SMACC2
st_acquire_sensors.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 StAcquireSensors : smacc2::SmaccState<StAcquireSensors, 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<CbWaitTransform, OrNavigation>, StStartNavigation, SUCCESS> >
34
36
37 // STATE FUNCTIONS
38 static void staticConfigure()
39 {
40 configure_orthogonal<OrNavigation, CbWaitTransform>("odom", "map", rclcpp::Duration(30000s));
41
42 //configure_orthogonal<OrNavigation, CbWaitPose>();
43 // configure_orthogonal<OrNavigation, CbWaitActionServer>(std::chrono::milliseconds(10000));
44 // configure_orthogonal<OrNavigation, CbWaitNav2Nodes>(std::vector<Nav2Nodes>{
45 // Nav2Nodes::PlannerServer, Nav2Nodes::ControllerServer, Nav2Nodes::BtNavigator});
46 }
47
48
49
51 {
52 // illegal wait workaround
53 // rclcpp::sleep_for(6s);
54
55 // ClNav2Z * navClient;
56 // getOrthogonal<OrNavigation>()->requiresClient(navClient);
57
58 // amcl_ = navClient->getComponent<Amcl>();
59 }
60
61 void onEntry()
62 {
63 //sendInitialPoseEstimation();
64 //auto res = exec("ros2");
65 //RCLCPP_INFO(getLogger(), "launch result: %s", res.c_str());
66 }
67
69 {
70 geometry_msgs::msg::PoseWithCovarianceStamped initialposemsg;
71 //bool useSimTime = getNode()->get_parameter("use_sim_time").as_bool();
72 //getNode()->set_parameter("use_sim_time",true);
73
74 initialposemsg.header.stamp = getNode()->now();
75 initialposemsg.header.frame_id = "map";
76
77 initialposemsg.pose.pose.position.x = 3.415412425994873;
78 initialposemsg.pose.pose.position.y = 2.0;
79 initialposemsg.pose.pose.position.z = 0;
80
81 initialposemsg.pose.pose.orientation.x = 0;
82 initialposemsg.pose.pose.orientation.y = 0;
83 initialposemsg.pose.pose.orientation.z = 1;
84 initialposemsg.pose.pose.orientation.w = 0;
85
86 //z: 0.9999985465626609
87 // w: 0.00170495529732811
88
89 initialposemsg.pose.covariance = {
90 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0,
91 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
92 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853891909122467};
93
94 amcl_->setInitialPose(initialposemsg);
95 }
96
97 void onExit() {}
98};
99} // namespace sm_aws_warehouse_navigation
void setInitialPose(const geometry_msgs::msg::PoseWithCovarianceStamped &initialpose)
Definition: amcl.cpp:38
rclcpp::Node::SharedPtr & getNode()
Definition: smacc_state.hpp:34
mpl::list< Transition< EvCbSuccess< CbWaitTransform, OrNavigation >, StStartNavigation, SUCCESS > > reactions