Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactored output parameter. #115

Merged
merged 2 commits into from
Mar 7, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions include/path_tracking_pid/path_tracking_pid_local_planner.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,10 +90,9 @@ class TrackingPidLocalPlanner : public mbf_costmap_core::CostmapController,
private:
/**
* @brief Calculates the velocity command based on the current robot pose given by pose.
* @param cmd_vel Output the velocity command
* @return true if succeded.
* @return Velocity command on success, empty optional otherwise.
*/
bool computeVelocityCommands(geometry_msgs::Twist & cmd_vel);
std::optional<geometry_msgs::Twist> computeVelocityCommands();

/**
* @brief Returns true, if the goal is reached.
Expand Down
20 changes: 12 additions & 8 deletions src/path_tracking_pid_local_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,7 @@ bool TrackingPidLocalPlanner::setPlan(const std::vector<geometry_msgs::PoseStamp
return true;
}

bool TrackingPidLocalPlanner::computeVelocityCommands(geometry_msgs::Twist & cmd_vel)
std::optional<geometry_msgs::Twist> TrackingPidLocalPlanner::computeVelocityCommands()
{
ros::Time now = ros::Time::now();
if (prev_time_.isZero()) {
Expand All @@ -219,22 +219,25 @@ bool TrackingPidLocalPlanner::computeVelocityCommands(geometry_msgs::Twist & cmd
if (dt.isZero()) {
ROS_ERROR_THROTTLE(
5, "dt=0 detected, skipping loop(s). Possible overloaded cpu or simulating too fast");
cmd_vel = geometry_msgs::Twist();
auto cmd_vel = geometry_msgs::Twist();
cmd_vel.linear.x = pid_controller_.getControllerState().current_x_vel;
cmd_vel.angular.z = pid_controller_.getControllerState().current_yaw_vel;
return true; // False is no use: https://github.com/magazino/move_base_flex/issues/195
// At the first call of computeVelocityCommands() we can't calculate a cmd_vel. We can't return
// false because of https://github.com/magazino/move_base_flex/issues/195 so the current
// velocity is send instead.
return cmd_vel;
}
if (dt < ros::Duration(0) || dt > ros::Duration(DT_MAX)) {
ROS_ERROR("Invalid time increment: %f. Aborting", dt.toSec());
return false;
return std::nullopt;
}
try {
ROS_DEBUG("map_frame: %s, base_link_frame: %s", map_frame_.c_str(), base_link_frame_.c_str());
tfCurPoseStamped_ = tf_->lookupTransform(map_frame_, base_link_frame_, ros::Time(0));
} catch (const tf2::TransformException & ex) {
ROS_ERROR("Received an exception trying to transform: %s", ex.what());
active_goal_ = false;
return false;
return std::nullopt;
}

// Handle obstacles
Expand All @@ -258,7 +261,6 @@ bool TrackingPidLocalPlanner::computeVelocityCommands(geometry_msgs::Twist & cmd

const auto update_result = pid_controller_.update_with_limits(
tf2_convert<tf2::Transform>(tfCurPoseStamped_.transform), latest_odom_.twist.twist, dt);
cmd_vel = update_result.velocity_command;

path_tracking_pid::PidFeedback feedback_msg;
feedback_msg.eda = ros::Duration(update_result.eda);
Expand Down Expand Up @@ -296,7 +298,7 @@ bool TrackingPidLocalPlanner::computeVelocityCommands(geometry_msgs::Twist & cmd
prev_time_ = now;
prev_dt_ =
dt; // Store last known valid dt for next cycles (https://github.com/magazino/move_base_flex/issues/195)
return true;
return update_result.velocity_command;
}

uint8_t TrackingPidLocalPlanner::projectedCollisionCost()
Expand Down Expand Up @@ -441,10 +443,12 @@ uint32_t TrackingPidLocalPlanner::computeVelocityCommands(
return mbf_msgs::ExePathResult::NOT_INITIALIZED;
}
// TODO(Cesar): Use provided pose and odom
if (!computeVelocityCommands(cmd_vel.twist)) {
const auto opt_cmd_vel = computeVelocityCommands();
if (!opt_cmd_vel) {
active_goal_ = false;
return mbf_msgs::ExePathResult::FAILURE;
}
cmd_vel.twist = *opt_cmd_vel;
cmd_vel.header.stamp = ros::Time::now();
cmd_vel.header.frame_id = base_link_frame_;

Expand Down