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_ = node->create_subscription<geometry_msgs::msg::Twist>(
54 cmd_vel_teleop, rclcpp::SystemDefaultsQoS(),
56 &AssistedTeleop::teleopVelocityCallback,
57 this, std::placeholders::_1));
59 preempt_teleop_sub_ = node->create_subscription<std_msgs::msg::Empty>(
60 "preempt_teleop", rclcpp::SystemDefaultsQoS(),
62 &AssistedTeleop::preemptTeleopCallback,
63 this, std::placeholders::_1));
66 Status AssistedTeleop::onRun(
const std::shared_ptr<const AssistedTeleopAction::Goal> command)
68 preempt_teleop_ =
false;
69 command_time_allowance_ = command->time_allowance;
70 end_time_ = this->clock_->now() + command_time_allowance_;
71 return Status::SUCCEEDED;
74 void AssistedTeleop::onActionCompletion()
76 teleop_twist_ = geometry_msgs::msg::Twist();
77 preempt_teleop_ =
false;
80 Status AssistedTeleop::onCycleUpdate()
82 feedback_->current_teleop_duration = elasped_time_;
83 action_server_->publish_feedback(feedback_);
85 rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
86 if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
90 "Exceeded time allowance before reaching the " << behavior_name_.c_str() <<
91 "goal - Exiting " << behavior_name_.c_str());
92 return Status::FAILED;
96 if (preempt_teleop_) {
98 return Status::SUCCEEDED;
101 geometry_msgs::msg::PoseStamped current_pose;
102 if (!nav2_util::getCurrentPose(
103 current_pose, *tf_, global_frame_, robot_base_frame_,
104 transform_tolerance_))
108 "Current robot pose is not available for " <<
109 behavior_name_.c_str());
110 return Status::FAILED;
112 geometry_msgs::msg::Pose2D projected_pose;
113 projected_pose.x = current_pose.pose.position.x;
114 projected_pose.y = current_pose.pose.position.y;
115 projected_pose.theta = tf2::getYaw(current_pose.pose.orientation);
117 geometry_msgs::msg::Twist scaled_twist = teleop_twist_;
118 for (
double time = simulation_time_step_; time < projection_time_;
119 time += simulation_time_step_)
121 projected_pose = projectPose(projected_pose, teleop_twist_, simulation_time_step_);
123 if (!collision_checker_->isCollisionFree(projected_pose)) {
124 if (time == simulation_time_step_) {
125 RCLCPP_DEBUG_STREAM_THROTTLE(
129 behavior_name_.c_str() <<
" collided on first time step, setting velocity to zero");
130 scaled_twist.linear.x = 0.0f;
131 scaled_twist.linear.y = 0.0f;
132 scaled_twist.angular.z = 0.0f;
135 RCLCPP_DEBUG_STREAM_THROTTLE(
139 behavior_name_.c_str() <<
" collision approaching in " << time <<
" seconds");
140 double scale_factor = time / projection_time_;
141 scaled_twist.linear.x *= scale_factor;
142 scaled_twist.linear.y *= scale_factor;
143 scaled_twist.angular.z *= scale_factor;
148 vel_pub_->publish(std::move(scaled_twist));
150 return Status::RUNNING;
153 geometry_msgs::msg::Pose2D AssistedTeleop::projectPose(
154 const geometry_msgs::msg::Pose2D & pose,
155 const geometry_msgs::msg::Twist & twist,
156 double projection_time)
158 geometry_msgs::msg::Pose2D projected_pose = pose;
160 projected_pose.x += projection_time * (
161 twist.linear.x * cos(pose.theta) +
162 twist.linear.y * sin(pose.theta));
164 projected_pose.y += projection_time * (
165 twist.linear.x * sin(pose.theta) -
166 twist.linear.y * cos(pose.theta));
168 projected_pose.theta += projection_time * twist.angular.z;
170 return projected_pose;
173 void AssistedTeleop::teleopVelocityCallback(
const geometry_msgs::msg::Twist::SharedPtr msg)
175 teleop_twist_ = *msg;
178 void AssistedTeleop::preemptTeleopCallback(
const std_msgs::msg::Empty::SharedPtr)
180 preempt_teleop_ =
true;
185 #include "pluginlib/class_list_macros.hpp"
An action server behavior for assisted teleop.
Abstract interface for behaviors to adhere to with pluginlib.