20#include <geometry_msgs/msg/quaternion_stamped.hpp>
32: rotateDegree(rotate_degree), spinningPlanner(spinning_planner)
48 plannerSwitcher->setDefaultPlanners();
53 auto currentPoseMsg = p->toPoseMsg();
55 tf2::Transform currentPose;
56 tf2::fromMsg(currentPoseMsg, currentPose);
60 goal.pose.header.frame_id = referenceFrame;
63 auto currentAngle = tf2::getYaw(currentPoseMsg.orientation);
64 auto targetAngle = currentAngle + angle_increment_degree * M_PI / 180.0;
65 goal.pose.pose.position = currentPoseMsg.position;
67 q.setRPY(0, 0, targetAngle);
68 goal.pose.pose.orientation = tf2::toMsg(q);
70 geometry_msgs::msg::PoseStamped stampedCurrentPoseMsg;
71 stampedCurrentPoseMsg.header.frame_id = referenceFrame;
72 stampedCurrentPoseMsg.header.stamp =
getNode()->now();
73 stampedCurrentPoseMsg.pose = currentPoseMsg;
77 odomTracker->pushPath(pathname);
79 odomTracker->setStartPoint(stampedCurrentPoseMsg);
82 RCLCPP_INFO_STREAM(
getLogger(),
"current pose: " << currentPoseMsg);
83 RCLCPP_INFO_STREAM(
getLogger(),
"goal pose: " << goal.pose.pose);
void sendGoal(ClNav2Z::Goal &goal)
cl_nav2z::ClNav2Z * nav2zClient_
std::optional< cl_nav2z::SpinningPlanner > spinningPlanner
CbRotate(float rotate_degree)
void setPureSpinningPlanner(bool commit=true)
const std::string & getReferenceFrame() const
ISmaccState * getCurrentState()
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
void requiresClient(SmaccClientType *&storage)
TComponent * getComponent()
virtual std::string getName()=0
typename ActionClient::Goal Goal