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

feat(tier4_planning_rviz_plugins): add vehicle_info to Footprint Displays #712

Merged
merged 3 commits into from
Apr 23, 2022
Merged
Show file tree
Hide file tree
Changes from 2 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
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <rviz_common/properties/float_property.hpp>
#include <rviz_common/properties/parse_color.hpp>
#include <rviz_common/validate_floats.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/path.hpp>

Expand All @@ -37,6 +38,9 @@

namespace rviz_plugins
{
using vehicle_info_util::VehicleInfo;
using vehicle_info_util::VehicleInfoUtil;

class AutowarePathFootprintDisplay
: public rviz_common::MessageFilterDisplay<autoware_auto_planning_msgs::msg::Path>
{
Expand Down Expand Up @@ -72,6 +76,8 @@ private Q_SLOTS:
}
float length, width, rear_overhang;
};

std::shared_ptr<VehicleInfo> vehicle_info_;
std::shared_ptr<VehicleFootprintInfo> vehicle_footprint_info_;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <rviz_common/properties/float_property.hpp>
#include <rviz_common/properties/parse_color.hpp>
#include <rviz_common/validate_floats.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

Expand All @@ -37,6 +38,9 @@

namespace rviz_plugins
{
using vehicle_info_util::VehicleInfo;
using vehicle_info_util::VehicleInfoUtil;

class AutowarePathWithLaneIdFootprintDisplay
: public rviz_common::MessageFilterDisplay<autoware_auto_planning_msgs::msg::PathWithLaneId>
{
Expand Down Expand Up @@ -72,6 +76,7 @@ private Q_SLOTS:
}
float length, width, rear_overhang;
};
std::shared_ptr<VehicleInfo> vehicle_info_;
std::shared_ptr<VehicleFootprintInfo> vehicle_footprint_info_;

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <rviz_common/properties/float_property.hpp>
#include <rviz_common/properties/parse_color.hpp>
#include <rviz_common/validate_floats.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_auto_planning_msgs/msg/trajectory.hpp>

Expand All @@ -37,6 +38,9 @@

namespace rviz_plugins
{
using vehicle_info_util::VehicleInfo;
using vehicle_info_util::VehicleInfoUtil;

class AutowareTrajectoryFootprintDisplay
: public rviz_common::MessageFilterDisplay<autoware_auto_planning_msgs::msg::Trajectory>
{
Expand Down Expand Up @@ -79,6 +83,7 @@ private Q_SLOTS:
}
float length, width, rear_overhang;
};
std::shared_ptr<VehicleInfo> vehicle_info_;
std::shared_ptr<VehicleFootprintInfo> vehicle_footprint_info_;

private:
Expand Down
1 change: 1 addition & 0 deletions common/tier4_planning_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_planning_msgs</depend>
<depend>vehicle_info_util</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,20 @@ void AutowarePathFootprintDisplay::processMessage(
return;
}

// This doesn't work in the constructor.
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_THROTTLE(
rviz_ros_node_.lock()->get_raw_node()->get_logger(),
*rviz_ros_node_.lock()->get_raw_node()->get_clock(), 5000, "Failed to get vehicle_info: %s",
e.what());
}
}

Ogre::Vector3 position;
Ogre::Quaternion orientation;
if (!context_->getFrameManager()->getTransform(msg_ptr->header, position, orientation)) {
Expand Down Expand Up @@ -176,7 +190,13 @@ void AutowarePathFootprintDisplay::updateVehicleInfo()
float width{property_vehicle_width_->getFloat()};
float rear_overhang{property_rear_overhang_->getFloat()};

vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
if (vehicle_info_) {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(
vehicle_info_->vehicle_length_m, vehicle_info_->vehicle_width_m,
vehicle_info_->rear_overhang_m);
} else {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
kenji-miyake marked this conversation as resolved.
Show resolved Hide resolved
}
}

} // namespace rviz_plugins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,20 @@ void AutowarePathWithLaneIdFootprintDisplay::processMessage(
return;
}

// This doesn't work in the constructor.
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_THROTTLE(
rviz_ros_node_.lock()->get_raw_node()->get_logger(),
*rviz_ros_node_.lock()->get_raw_node()->get_clock(), 5000, "Failed to get vehicle_info: %s",
e.what());
}
}

Ogre::Vector3 position;
Ogre::Quaternion orientation;
if (!context_->getFrameManager()->getTransform(msg_ptr->header, position, orientation)) {
Expand Down Expand Up @@ -178,7 +192,13 @@ void AutowarePathWithLaneIdFootprintDisplay::updateVehicleInfo()
float width{property_vehicle_width_->getFloat()};
float rear_overhang{property_rear_overhang_->getFloat()};

vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
if (vehicle_info_) {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(
vehicle_info_->vehicle_length_m, vehicle_info_->vehicle_width_m,
vehicle_info_->rear_overhang_m);
} else {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
}
}

} // namespace rviz_plugins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,20 @@ void AutowareTrajectoryFootprintDisplay::processMessage(
return;
}

// This doesn't work in the constructor.
if (!vehicle_info_) {
try {
vehicle_info_ = std::make_shared<VehicleInfo>(
VehicleInfoUtil(*rviz_ros_node_.lock()->get_raw_node()).getVehicleInfo());
updateVehicleInfo();
} catch (const std::exception & e) {
RCLCPP_WARN_THROTTLE(
rviz_ros_node_.lock()->get_raw_node()->get_logger(),
*rviz_ros_node_.lock()->get_raw_node()->get_clock(), 5000, "Failed to get vehicle_info: %s",
e.what());
}
}

Ogre::Vector3 position;
Ogre::Quaternion orientation;
if (!context_->getFrameManager()->getTransform(msg_ptr->header, position, orientation)) {
Expand Down Expand Up @@ -241,7 +255,13 @@ void AutowareTrajectoryFootprintDisplay::updateVehicleInfo()
float width{property_vehicle_width_->getFloat()};
float rear_overhang{property_rear_overhang_->getFloat()};

vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
if (vehicle_info_) {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(
vehicle_info_->vehicle_length_m, vehicle_info_->vehicle_width_m,
vehicle_info_->rear_overhang_m);
} else {
vehicle_footprint_info_ = std::make_shared<VehicleFootprintInfo>(length, width, rear_overhang);
}
}

} // namespace rviz_plugins
Expand Down