24#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
25#include "rclcpp/rclcpp.hpp"
39#include "ros_timer_client/client_behaviors/cb_timer_countdown_once.hpp"
58 using SmaccState::SmaccState;
61 typedef boost::mpl::list<
71 geometry_msgs::msg::PoseWithCovarianceStamped initialLocationEstimation;
73 initialLocationEstimation.pose.pose.position.x = -61.46;
74 initialLocationEstimation.pose.pose.position.y = -41.25;
75 initialLocationEstimation.pose.pose.position.z = 0;
77 initialLocationEstimation.pose.pose.orientation.x = 0;
78 initialLocationEstimation.pose.pose.orientation.y = 0;
79 initialLocationEstimation.pose.pose.orientation.z = -0.9851278757214282;
80 initialLocationEstimation.pose.pose.orientation.w = 0.171822782181485;
82 initialLocationEstimation.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.06853891945200942};
87 configure_orthogonal<OrAutowareAuto, CbSetupInitialPoseEstimation>(initialLocationEstimation);
88 configure_orthogonal<OrTimer, CbTimerCountdownOnce>(5);
rclcpp::Logger getLogger()
boost::mpl::list< Transition< sm_autoware_avp::clients::EvAutoLocalized< sm_autoware_avp::clients::ClAutoware, OrAutowareAuto >, StNavigateWaypoint1, SUCCESS >, Transition< EvTimer< CbTimerCountdownOnce, OrTimer >, StSetupInitialLocationEstimation, ABORT > > reactions
static void staticConfigure()