17 #include "nav2_behaviors/plugins/assisted_teleop.hpp"
18 #include "nav2_util/node_utils.hpp"
20 namespace nav2_behaviors
22 AssistedTeleop::AssistedTeleop()
23 : TimedBehavior<AssistedTeleopAction>(),
24 feedback_(std::make_shared<AssistedTeleopAction::Feedback>())
27 void AssistedTeleop::onConfigure()
29 auto node = node_.lock();
31 throw std::runtime_error{
"Failed to lock node"};
35 nav2_util::declare_parameter_if_not_declared(
37 "projection_time", rclcpp::ParameterValue(1.0));
39 nav2_util::declare_parameter_if_not_declared(
41 "simulation_time_step", rclcpp::ParameterValue(0.1));
43 nav2_util::declare_parameter_if_not_declared(
45 "cmd_vel_teleop", rclcpp::ParameterValue(std::string(
"cmd_vel_teleop")));
47 node->get_parameter(
"projection_time", projection_time_);
48 node->get_parameter(
"simulation_time_step", simulation_time_step_);
50 std::string cmd_vel_teleop;
51 node->get_parameter(
"cmd_vel_teleop", cmd_vel_teleop);
53 vel_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
55 cmd_vel_teleop, rclcpp::SystemDefaultsQoS(),
56 [&](geometry_msgs::msg::Twist::SharedPtr msg) {
57 teleop_twist_.twist = *msg;
58 }, [&](geometry_msgs::msg::TwistStamped::SharedPtr msg) {
62 preempt_teleop_sub_ = node->create_subscription<std_msgs::msg::Empty>(
63 "preempt_teleop", rclcpp::SystemDefaultsQoS(),
65 &AssistedTeleop::preemptTeleopCallback,
66 this, std::placeholders::_1));
69 ResultStatus AssistedTeleop::onRun(
const std::shared_ptr<const AssistedTeleopAction::Goal> command)
71 preempt_teleop_ =
false;
72 command_time_allowance_ = command->time_allowance;
73 end_time_ = this->clock_->now() + command_time_allowance_;
74 return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE};
77 void AssistedTeleop::onActionCompletion(std::shared_ptr<AssistedTeleopActionResult>)
79 teleop_twist_ = geometry_msgs::msg::TwistStamped();
80 preempt_teleop_ =
false;
85 feedback_->current_teleop_duration = elasped_time_;
86 action_server_->publish_feedback(feedback_);
88 rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
89 if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
93 "Exceeded time allowance before reaching the " << behavior_name_.c_str() <<
94 "goal - Exiting " << behavior_name_.c_str());
95 return ResultStatus{Status::FAILED, AssistedTeleopActionResult::TIMEOUT};
99 if (preempt_teleop_) {
101 return ResultStatus{Status::SUCCEEDED, AssistedTeleopActionResult::NONE};
104 geometry_msgs::msg::PoseStamped current_pose;
105 if (!nav2_util::getCurrentPose(
106 current_pose, *tf_, local_frame_, robot_base_frame_,
107 transform_tolerance_))
111 "Current robot pose is not available for " <<
112 behavior_name_.c_str());
113 return ResultStatus{Status::FAILED, AssistedTeleopActionResult::TF_ERROR};
116 geometry_msgs::msg::Pose2D projected_pose;
117 projected_pose.x = current_pose.pose.position.x;
118 projected_pose.y = current_pose.pose.position.y;
119 projected_pose.theta = tf2::getYaw(current_pose.pose.orientation);
121 auto scaled_twist = std::make_unique<geometry_msgs::msg::TwistStamped>(teleop_twist_);
122 for (
double time = simulation_time_step_; time < projection_time_;
123 time += simulation_time_step_)
125 projected_pose = projectPose(projected_pose, teleop_twist_.twist, simulation_time_step_);
127 if (!local_collision_checker_->isCollisionFree(projected_pose)) {
128 if (time == simulation_time_step_) {
129 RCLCPP_DEBUG_STREAM_THROTTLE(
133 behavior_name_.c_str() <<
" collided on first time step, setting velocity to zero");
134 scaled_twist->twist.linear.x = 0.0f;
135 scaled_twist->twist.linear.y = 0.0f;
136 scaled_twist->twist.angular.z = 0.0f;
139 RCLCPP_DEBUG_STREAM_THROTTLE(
143 behavior_name_.c_str() <<
" collision approaching in " << time <<
" seconds");
144 double scale_factor = time / projection_time_;
145 scaled_twist->twist.linear.x *= scale_factor;
146 scaled_twist->twist.linear.y *= scale_factor;
147 scaled_twist->twist.angular.z *= scale_factor;
152 vel_pub_->publish(std::move(scaled_twist));
154 return ResultStatus{Status::RUNNING, AssistedTeleopActionResult::NONE};
157 geometry_msgs::msg::Pose2D AssistedTeleop::projectPose(
158 const geometry_msgs::msg::Pose2D & pose,
159 const geometry_msgs::msg::Twist & twist,
160 double projection_time)
162 geometry_msgs::msg::Pose2D projected_pose = pose;
164 projected_pose.x += projection_time * (
165 twist.linear.x * cos(pose.theta) +
166 twist.linear.y * sin(pose.theta));
168 projected_pose.y += projection_time * (
169 twist.linear.x * sin(pose.theta) -
170 twist.linear.y * cos(pose.theta));
172 projected_pose.theta += projection_time * twist.angular.z;
174 return projected_pose;
177 void AssistedTeleop::preemptTeleopCallback(
const std_msgs::msg::Empty::SharedPtr)
179 preempt_teleop_ =
true;
184 #include "pluginlib/class_list_macros.hpp"
An action server behavior for assisted teleop.
Abstract interface for behaviors to adhere to with pluginlib.