30using ::cl_nav2z::odom_tracker::OdomTracker;
31using ::cl_nav2z::odom_tracker::WorkingMode;
33using ::cl_nav2z::Pose;
44 if (distance_meters < 0)
47 getLogger(),
"[" <<
getName() <<
"] negative forward distance: " << distance_meters
48 <<
". Resetting to 0.");
70 auto currentPoseMsg = p->toPoseMsg();
71 tf2::Transform currentPose;
72 tf2::fromMsg(currentPoseMsg, currentPose);
76 <<
"current pose: " << currentPoseMsg);
85 <<
"Forcing initial straight motion orientation: " << currentPoseMsg.orientation);
88 tf2::Transform targetPose;
91 tf2::fromMsg(
goalPose_->pose, targetPose);
96 tf2::Transform forwardDeltaTransform;
97 forwardDeltaTransform.setIdentity();
100 targetPose = currentPose * forwardDeltaTransform;
107 <<
"No goal Pose or Distance is specified. Aborting. No action request is sent."
108 << currentPoseMsg.orientation);
115 goal.pose.header.frame_id = referenceFrame;
117 tf2::toMsg(targetPose, goal.pose.pose);
120 <<
" TARGET POSE FORWARD: " << goal.pose.pose);
123 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
124 currentStampedPoseMsg.header.frame_id = referenceFrame;
125 currentStampedPoseMsg.header.stamp =
128 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
void sendGoal(ClNav2Z::Goal &goal)
cl_nav2z::ClNav2Z * nav2zClient_
std::optional< geometry_msgs::msg::PoseStamped > goalPose_
std::optional< float > forwardDistance_
CbNavigateForwardOptions options
void setForwardDistance(float distance_meters)
virtual ~CbNavigateForward()
odom_tracker::OdomTracker * odomTracker_
void setGoalCheckerId(std::string goal_checker_id)
void setForwardPlanner(bool commit=true)
const std::string & getReferenceFrame() const
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
ISmaccState * getCurrentState()
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
TComponent * getComponent()
virtual std::string getName()=0
typename ActionClient::Goal Goal
std::optional< float > forwardSpeed
std::optional< geometry_msgs::msg::Quaternion > forceInitialOrientation