18using namespace std::chrono_literals;
25 using SmaccState::SmaccState;
39 configure_orthogonal<OrNavigation, CbRosLaunch>();
40 configure_orthogonal<OrNavigation, CbWaitNav2Nodes>();
63 geometry_msgs::msg::PoseWithCovarianceStamped initialposemsg;
67 initialposemsg.header.stamp =
getNode()->now();
68 initialposemsg.header.frame_id =
"map";
70 initialposemsg.pose.pose.position.x = 3.415412425994873;
71 initialposemsg.pose.pose.position.y = 2.0;
72 initialposemsg.pose.pose.position.z = 0;
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;
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};
rclcpp::Node::SharedPtr & getNode()
mpl::list< Transition< EvCbSuccess< CbWaitNav2Nodes, OrNavigation >, StInitialNavigateForward, SUCCESS > > reactions
void sendInitialPoseEstimation()
static void staticConfigure()