Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
assisted_teleop.cpp
1 // Copyright (c) 2022 Joshua Wallace
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 #include <utility>
16 
17 #include "nav2_behaviors/plugins/assisted_teleop.hpp"
18 #include "nav2_ros_common/node_utils.hpp"
19 #include "nav2_util/geometry_utils.hpp"
20 
21 namespace nav2_behaviors
22 {
23 AssistedTeleop::AssistedTeleop()
24 : TimedBehavior<AssistedTeleopAction>(),
25  feedback_(std::make_shared<AssistedTeleopAction::Feedback>())
26 {}
27 
28 void AssistedTeleop::onConfigure()
29 {
30  auto node = node_.lock();
31  if (!node) {
32  throw std::runtime_error{"Failed to lock node"};
33  }
34 
35  // set up parameters
36  projection_time_ = node->declare_or_get_parameter("projection_time", 1.0);
37  simulation_time_step_ = node->declare_or_get_parameter("simulation_time_step", 0.1);
38  std::string cmd_vel_teleop = node->declare_or_get_parameter(
39  "cmd_vel_teleop", std::string("cmd_vel_teleop"));
40 
41  vel_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
42  node,
43  cmd_vel_teleop,
44  [&](geometry_msgs::msg::Twist::SharedPtr msg) {
45  teleop_twist_.twist = *msg;
46  }, [&](geometry_msgs::msg::TwistStamped::SharedPtr msg) {
47  teleop_twist_ = *msg;
48  });
49 
50  preempt_teleop_sub_ = node->create_subscription<std_msgs::msg::Empty>(
51  "preempt_teleop",
52  std::bind(
53  &AssistedTeleop::preemptTeleopCallback,
54  this, std::placeholders::_1));
55 }
56 
57 ResultStatus AssistedTeleop::onRun(const std::shared_ptr<const AssistedTeleopAction::Goal> command)
58 {
59  preempt_teleop_ = false;
60  command_time_allowance_ = command->time_allowance;
61  end_time_ = this->clock_->now() + command_time_allowance_;
62  return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE, ""};
63 }
64 
65 void AssistedTeleop::onActionCompletion(std::shared_ptr<AssistedTeleopActionResult>/*result*/)
66 {
67  teleop_twist_ = geometry_msgs::msg::TwistStamped();
68  preempt_teleop_ = false;
69 }
70 
71 ResultStatus AssistedTeleop::onCycleUpdate()
72 {
73  feedback_->current_teleop_duration = elapsed_time_;
74  action_server_->publish_feedback(feedback_);
75 
76  rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
77  if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
78  stopRobot();
79  std::string error_msg = "Exceeded time allowance before reaching the " + behavior_name_ +
80  "goal - Exiting " + behavior_name_;
81  RCLCPP_WARN_STREAM(logger_, error_msg.c_str());
82  return ResultStatus{Status::FAILED, AssistedTeleopActionResult::TIMEOUT, error_msg};
83  }
84 
85  // user states that teleop was successful
86  if (preempt_teleop_) {
87  stopRobot();
88  return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE, ""};
89  }
90 
91  geometry_msgs::msg::PoseStamped current_pose;
92  if (!nav2_util::getCurrentPose(
93  current_pose, *tf_, local_frame_, robot_base_frame_,
94  transform_tolerance_))
95  {
96  std::string error_msg = "Current robot pose is not available for " + behavior_name_;
97  RCLCPP_ERROR_STREAM(logger_, error_msg.c_str());
98  return ResultStatus{Status::FAILED, AssistedTeleopActionResult::TF_ERROR, error_msg};
99  }
100 
101  geometry_msgs::msg::Pose projected_pose = current_pose.pose;
102 
103  auto scaled_twist = std::make_unique<geometry_msgs::msg::TwistStamped>(teleop_twist_);
104  for (double time = simulation_time_step_; time < projection_time_;
105  time += simulation_time_step_)
106  {
107  projected_pose = projectPose(projected_pose, teleop_twist_.twist, simulation_time_step_);
108 
109  if (!local_collision_checker_->isCollisionFree(projected_pose)) {
110  if (time == simulation_time_step_) {
111  RCLCPP_DEBUG_STREAM_THROTTLE(
112  logger_,
113  *clock_,
114  1000,
115  behavior_name_.c_str() << " collided on first time step, setting velocity to zero");
116  scaled_twist->twist.linear.x = 0.0f;
117  scaled_twist->twist.linear.y = 0.0f;
118  scaled_twist->twist.angular.z = 0.0f;
119  break;
120  } else {
121  RCLCPP_DEBUG_STREAM_THROTTLE(
122  logger_,
123  *clock_,
124  1000,
125  behavior_name_.c_str() << " collision approaching in " << time << " seconds");
126  double scale_factor = time / projection_time_;
127  scaled_twist->twist.linear.x *= scale_factor;
128  scaled_twist->twist.linear.y *= scale_factor;
129  scaled_twist->twist.angular.z *= scale_factor;
130  break;
131  }
132  }
133  }
134  vel_pub_->publish(std::move(scaled_twist));
135 
136  return ResultStatus{Status::RUNNING, AssistedTeleopActionResult::NONE, ""};
137 }
138 
139 geometry_msgs::msg::Pose AssistedTeleop::projectPose(
140  const geometry_msgs::msg::Pose & pose,
141  const geometry_msgs::msg::Twist & twist,
142  double projection_time)
143 {
144  geometry_msgs::msg::Pose projected_pose = pose;
145 
146  double theta = tf2::getYaw(pose.orientation);
147 
148  projected_pose.position.x += projection_time * (
149  twist.linear.x * cos(theta) +
150  twist.linear.y * sin(theta));
151 
152  projected_pose.position.y += projection_time * (
153  twist.linear.x * sin(theta) -
154  twist.linear.y * cos(theta));
155 
156  double new_theta = theta + projection_time * twist.angular.z;
157  projected_pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(new_theta);
158 
159  return projected_pose;
160 }
161 
162 void AssistedTeleop::preemptTeleopCallback(const std_msgs::msg::Empty::SharedPtr)
163 {
164  preempt_teleop_ = true;
165 }
166 
167 } // namespace nav2_behaviors
168 
169 #include "pluginlib/class_list_macros.hpp"
An action server behavior for assisted teleop.
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:42