24#include "rclcpp/rclcpp.hpp"
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"
48 using SmaccState::SmaccState;
51 typedef boost::mpl::list<
62 geometry_msgs::msg::PoseStamped goal;
63 goal.header.frame_id =
"map";
64 goal.pose.position.x = -92.7;
65 goal.pose.position.y = 15.4;
66 goal.pose.position.z = 0;
68 goal.pose.orientation.z = -0.6221545523727376;
69 goal.pose.orientation.w = 0.7828944456067359;
71 configure_orthogonal<OrAutowareAuto, CbNavigateGlobalPosition>(goal);
72 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(12);
rclcpp::Logger getLogger()
static void staticConfigure()
boost::mpl::list< Transition< EvGoalReached< ClAutoware, OrAutowareAuto >, StSecondPause, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StNavigateWaypoint2, REPLAN > > reactions