Skip to content

Commit

Permalink
Merge pull request #232 from tier4/chore/cherry-pick-to-0.6.0
Browse files Browse the repository at this point in the history
chore: cherry pick PRs to 0.6.0
  • Loading branch information
0x126 authored Jan 4, 2023
2 parents d887e35 + d00c813 commit c4b243b
Show file tree
Hide file tree
Showing 5 changed files with 47 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -446,7 +446,7 @@ boost::optional<geometry_msgs::msg::Point> CrosswalkModule::findNearestStopPoint
const auto stop_line_distance = exist_stopline_in_map ? 0.0 : planner_param_.stop_line_distance;
const auto margin = stop_at_stop_line ? stop_line_distance + base_link2front
: planner_param_.stop_margin + base_link2front;
const auto stop_pose = calcLongitudinalOffsetPose(sparse_resample_path.points, p_stop, -margin);
const auto stop_pose = calcLongitudinalOffsetPose(ego_path.points, p_stop, -margin);

if (!stop_pose) {
return {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <rclcpp/rclcpp.hpp>

#include <tier4_debug_msgs/msg/string_stamped.hpp>
#include <tier4_planning_msgs/msg/velocity_limit.hpp>
#include <tier4_planning_msgs/msg/velocity_limit_clear_command.hpp>

Expand All @@ -25,10 +26,13 @@
#include <string>
#include <unordered_map>

using tier4_debug_msgs::msg::StringStamped;
using tier4_planning_msgs::msg::VelocityLimit;
using tier4_planning_msgs::msg::VelocityLimitClearCommand;
using tier4_planning_msgs::msg::VelocityLimitConstraints;

using VelocityLimitTable = std::unordered_map<std::string, VelocityLimit>;

class ExternalVelocityLimitSelectorNode : public rclcpp::Node
{
public:
Expand Down Expand Up @@ -58,18 +62,20 @@ class ExternalVelocityLimitSelectorNode : public rclcpp::Node
rclcpp::Subscription<VelocityLimit>::SharedPtr sub_external_velocity_limit_from_internal_;
rclcpp::Subscription<VelocityLimitClearCommand>::SharedPtr sub_velocity_limit_clear_command_;
rclcpp::Publisher<VelocityLimit>::SharedPtr pub_external_velocity_limit_;
rclcpp::Publisher<StringStamped>::SharedPtr pub_debug_string_;

void publishVelocityLimit(const VelocityLimit & velocity_limit);
void setVelocityLimitFromAPI(const VelocityLimit & velocity_limit);
void setVelocityLimitFromInternal(const VelocityLimit & velocity_limit);
void clearVelocityLimit(const std::string & sender);
void updateVelocityLimit();
void publishDebugString();
VelocityLimit getCurrentVelocityLimit() { return hardest_limit_; }

// Parameters
NodeParam node_param_{};
VelocityLimit hardest_limit_{};
std::unordered_map<std::string, VelocityLimit> velocity_limit_table_;
VelocityLimitTable velocity_limit_table_;
};

#endif // EXTERNAL_VELOCITY_LIMIT_SELECTOR__EXTERNAL_VELOCITY_LIMIT_SELECTOR_NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<arg name="input_velocity_limit_from_internal" default="/planning/scenario_planning/max_velocity_candidates"/>
<arg name="input_velocity_limit_clear_command_from_internal" default="/planning/scenario_planning/clear_velocity_limit"/>
<arg name="output_velocity_limit_from_selector" default="/planning/scenario_planning/max_velocity"/>
<arg name="output_debug_string" default="/planning/scenario_planning/external_velocity_limit_selector/debug"/>

<node pkg="external_velocity_limit_selector" exec="external_velocity_limit_selector" name="external_velocity_limit_selector" output="screen">
<param from="$(var common_param_path)"/>
Expand All @@ -16,5 +17,6 @@
<remap from="input/velocity_limit_from_internal" to="$(var input_velocity_limit_from_internal)"/>
<remap from="input/velocity_limit_clear_command_from_internal" to="$(var input_velocity_limit_clear_command_from_internal)"/>
<remap from="output/external_velocity_limit" to="$(var output_velocity_limit_from_selector)"/>
<remap from="output/debug" to="$(var output_debug_string)"/>
</node>
</launch>
1 change: 1 addition & 0 deletions planning/external_velocity_limit_selector/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tier4_debug_msgs</depend>
<depend>tier4_planning_msgs</depend>

<exec_depend>ros2cli</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
namespace
{
VelocityLimit getHardestLimit(
const std::unordered_map<std::string, VelocityLimit> & velocity_limits,
const VelocityLimitTable & velocity_limits,
const ExternalVelocityLimitSelectorNode::NodeParam & node_param)
{
VelocityLimit hardest_limit{};
Expand Down Expand Up @@ -65,6 +65,23 @@ VelocityLimit getHardestLimit(

return hardest_limit;
}

std::string getDebugString(const VelocityLimitTable & velocity_limits)
{
std::ostringstream string_stream;
string_stream << std::boolalpha << std::fixed << std::setprecision(2);
for (const auto & limit : velocity_limits) {
string_stream << "[" << limit.first << "]";
string_stream << "(";
string_stream << limit.second.use_constraints << ",";
string_stream << limit.second.max_velocity << ",";
string_stream << limit.second.constraints.min_acceleration << ",";
string_stream << limit.second.constraints.min_jerk << ",";
string_stream << limit.second.constraints.max_jerk << ")";
}

return string_stream.str();
}
} // namespace

ExternalVelocityLimitSelectorNode::ExternalVelocityLimitSelectorNode(
Expand All @@ -78,17 +95,19 @@ ExternalVelocityLimitSelectorNode::ExternalVelocityLimitSelectorNode(
std::bind(&ExternalVelocityLimitSelectorNode::onVelocityLimitFromAPI, this, _1));

sub_external_velocity_limit_from_internal_ = this->create_subscription<VelocityLimit>(
"input/velocity_limit_from_internal", rclcpp::QoS{1}.transient_local(),
"input/velocity_limit_from_internal", rclcpp::QoS{10}.transient_local(),
std::bind(&ExternalVelocityLimitSelectorNode::onVelocityLimitFromInternal, this, _1));

sub_velocity_limit_clear_command_ = this->create_subscription<VelocityLimitClearCommand>(
"input/velocity_limit_clear_command_from_internal", rclcpp::QoS{1}.transient_local(),
"input/velocity_limit_clear_command_from_internal", rclcpp::QoS{10}.transient_local(),
std::bind(&ExternalVelocityLimitSelectorNode::onVelocityLimitClearCommand, this, _1));

// Output
pub_external_velocity_limit_ =
this->create_publisher<VelocityLimit>("output/external_velocity_limit", 1);

pub_debug_string_ = this->create_publisher<StringStamped>("output/debug", 1);

// Params
{
auto & p = node_param_;
Expand All @@ -112,6 +131,8 @@ void ExternalVelocityLimitSelectorNode::onVelocityLimitFromAPI(

const auto velocity_limit = getCurrentVelocityLimit();
publishVelocityLimit(velocity_limit);

publishDebugString();
}

void ExternalVelocityLimitSelectorNode::onVelocityLimitFromInternal(
Expand All @@ -122,6 +143,8 @@ void ExternalVelocityLimitSelectorNode::onVelocityLimitFromInternal(

const auto velocity_limit = getCurrentVelocityLimit();
publishVelocityLimit(velocity_limit);

publishDebugString();
}

void ExternalVelocityLimitSelectorNode::onVelocityLimitClearCommand(
Expand All @@ -135,13 +158,23 @@ void ExternalVelocityLimitSelectorNode::onVelocityLimitClearCommand(

const auto velocity_limit = getCurrentVelocityLimit();
publishVelocityLimit(velocity_limit);

publishDebugString();
}

void ExternalVelocityLimitSelectorNode::publishVelocityLimit(const VelocityLimit & velocity_limit)
{
pub_external_velocity_limit_->publish(velocity_limit);
}

void ExternalVelocityLimitSelectorNode::publishDebugString()
{
StringStamped debug_string{};
debug_string.stamp = this->now();
debug_string.data = getDebugString(velocity_limit_table_);
pub_debug_string_->publish(debug_string);
}

void ExternalVelocityLimitSelectorNode::setVelocityLimitFromAPI(
const VelocityLimit & velocity_limit)
{
Expand Down

0 comments on commit c4b243b

Please sign in to comment.