SMACC2
Loading...
Searching...
No Matches
cb_navigate_forward.cpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
22
27
28namespace cl_nav2z
29{
30using ::cl_nav2z::odom_tracker::CpOdomTracker;
31using ::cl_nav2z::odom_tracker::WorkingMode;
32
33using ::cl_nav2z::Pose;
34
35CbNavigateForward::CbNavigateForward(float distance_meters) : forwardDistance_(distance_meters) {}
37
38CbNavigateForward::CbNavigateForward(geometry_msgs::msg::PoseStamped goal) : goalPose_(goal) {}
39
41
42void CbNavigateForward::setForwardDistance(float distance_meters)
43{
44 if (distance_meters < 0)
45 {
46 RCLCPP_INFO_STREAM(
47 getLogger(), "[" << getName() << "] negative forward distance: " << distance_meters
48 << ". Resetting to 0.");
49 distance_meters = 0;
50 }
51 forwardDistance_ = distance_meters;
52
53 RCLCPP_INFO_STREAM(
54 getLogger(), "[" << getName() << "] setting fw motion distance: " << *forwardDistance_);
55}
56
58{
60 {
62
63 RCLCPP_INFO_STREAM(
64 getLogger(), "[" << getName() << "] Straight motion distance: " << *forwardDistance_);
65 }
66
67 // get current pose
68 auto p = nav2zClient_->getComponent<Pose>();
69 auto referenceFrame = p->getReferenceFrame();
70 auto currentPoseMsg = p->toPoseMsg();
71
72 RCLCPP_INFO_STREAM(
73 getLogger(), "[" << getName() << "]"
74 << "current pose: " << currentPoseMsg);
75
76 // force global orientation if it is requested
78 {
79 currentPoseMsg.orientation = *(options.forceInitialOrientation);
80 RCLCPP_WARN_STREAM(
81 getLogger(),
82 "[" << getName() << "]"
83 << "Forcing initial straight motion orientation: " << currentPoseMsg.orientation);
84 }
85
86 tf2::Transform currentPose;
87 tf2::fromMsg(currentPoseMsg, currentPose);
88
89 tf2::Transform targetPose;
90 if (goalPose_)
91 {
92 tf2::fromMsg(goalPose_->pose, targetPose);
93 }
94 else if (forwardDistance_)
95 {
96 // compute forward goal pose
97 tf2::Transform forwardDeltaTransform;
98 forwardDeltaTransform.setIdentity();
99 forwardDeltaTransform.setOrigin(tf2::Vector3(*forwardDistance_, 0, 0));
100
101 targetPose = currentPose * forwardDeltaTransform;
102 }
103 else
104 {
105 RCLCPP_WARN_STREAM(
106 getLogger(),
107 "[" << getName() << "]"
108 << "No goal Pose or Distance is specified. Aborting. No action request is sent."
109 << currentPoseMsg.orientation);
110
111 return;
112 }
113
114 // action goal
115 ClNav2Z::Goal goal;
116 goal.pose.header.frame_id = referenceFrame;
117 //goal.pose.header.stamp = getNode()->now();
118 tf2::toMsg(targetPose, goal.pose.pose);
119 RCLCPP_INFO_STREAM(
120 getLogger(), "[" << getName() << "]"
121 << " TARGET POSE FORWARD: " << goal.pose.pose);
122
123 // current pose
124 geometry_msgs::msg::PoseStamped currentStampedPoseMsg;
125 currentStampedPoseMsg.header.frame_id = referenceFrame;
126 currentStampedPoseMsg.header.stamp =
127 getNode()->now(); // probably it is better avoid setting that goal timestamp
128
129 tf2::toMsg(currentPose, currentStampedPoseMsg.pose);
130
132 if (odomTracker_ != nullptr)
133 {
134 auto pathname = this->getCurrentState()->getName() + " - " + getName();
135 odomTracker_->pushPath(pathname);
136 odomTracker_->setStartPoint(currentStampedPoseMsg);
138 odomTracker_->setWorkingMode(WorkingMode::RECORD_PATH);
139 }
140
141 auto plannerSwitcher = nav2zClient_->getComponent<CpPlannerSwitcher>();
142 plannerSwitcher->setForwardPlanner();
143
144 auto goalCheckerSwitcher = nav2zClient_->getComponent<CpGoalCheckerSwitcher>();
145 goalCheckerSwitcher->setGoalCheckerId("forward_goal_checker");
146
147 this->sendGoal(goal);
148}
149
151{
152 if (odomTracker_)
153 {
154 this->odomTracker_->setWorkingMode(WorkingMode::IDLE);
155 }
156}
157
158} // namespace cl_nav2z
std::optional< geometry_msgs::msg::PoseStamped > goalPose_
std::optional< float > forwardDistance_
CbNavigateForwardOptions options
void setForwardDistance(float distance_meters)
odom_tracker::CpOdomTracker * odomTracker_
void setGoalCheckerId(std::string goal_checker_id)
void setForwardPlanner(bool commit=true)
const std::string & getReferenceFrame() const
Definition cp_pose.hpp:76
void setCurrentMotionGoal(const geometry_msgs::msg::PoseStamped &pose)
void setWorkingMode(WorkingMode workingMode)
void setStartPoint(const geometry_msgs::msg::PoseStamped &pose)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
virtual std::string getName()=0
std::optional< geometry_msgs::msg::Quaternion > forceInitialOrientation