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"
51 using SmaccState::SmaccState;
54 typedef boost::mpl::list<
66 geometry_msgs::msg::PoseStamped goal;
68 goal.header.frame_id =
"map";
69 goal.pose.position.x = -45.253597259521484;
70 goal.pose.position.y = 93.64368438720703;
71 goal.pose.position.z = 0;
73 goal.pose.orientation.z = 0.34841036522579555;
74 goal.pose.orientation.w = 0.9373421026515494;
76 configure_orthogonal<OrAutowareAuto, CbNavigateGlobalPosition>(goal);
77 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5);
rclcpp::Logger getLogger()
static void staticConfigure()
boost::mpl::list< Transition< EvGoalReached< ClAutoware, OrAutowareAuto >, StFirstPause, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StNavigateWaypoint1, REPLAN > > reactions