Skip to content

Commit

Permalink
Update to shared_ptr API
Browse files Browse the repository at this point in the history
  • Loading branch information
mxgrey committed Mar 19, 2022
1 parent c9cc30a commit 297b02d
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 8 deletions.
10 changes: 5 additions & 5 deletions rmf_visualization_schedule/src/ScheduleMarkerPublisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,12 +209,12 @@ class ScheduleMarkerPublisher : public rclcpp::Node
{
active_id.push_back(element.participant);

if (element.route.trajectory().find(traj_param.start_time) !=
element.route.trajectory().end())
if (element.route->trajectory().find(traj_param.start_time) !=
element.route->trajectory().end())
{
add_location_markers(marker_array.markers, element, traj_param);
}
if (traj_param.start_time < *element.route.trajectory().finish_time())
if (traj_param.start_time < *element.route->trajectory().finish_time())
{
auto path_marker = make_path_marker(element, traj_param);
marker_array.markers.push_back(path_marker);
Expand Down Expand Up @@ -499,7 +499,7 @@ class ScheduleMarkerPublisher : public rclcpp::Node
const RequestParam& param)
{
// TODO Link the color, shape and size of marker to profile of trajectory
const auto& trajectory = element.route.trajectory();
const auto& trajectory = element.route->trajectory();

// Find the pose of the markers
const auto it = trajectory.find(param.start_time);
Expand All @@ -522,7 +522,7 @@ class ScheduleMarkerPublisher : public rclcpp::Node
const RequestParam param)
{
// TODO Link the color, shape and size of marker to profile of trajectory
const auto& trajectory = element.route.trajectory();
const auto& trajectory = element.route->trajectory();
const bool conflict = is_conflict(element.participant);

Marker marker_msg;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,13 @@ auto ScheduleDataNode::get_negotiation_trajectories(
(const rmf_traffic::Route& route,
rmf_traffic::schedule::ParticipantId id)
{
Element e { id, 0, route_id, route, *table_view->get_description(id) };
Element e {
id,
0,
route_id,
std::make_shared<rmf_traffic::Route>(route),
*table_view->get_description(id)
};
trajectory_elements.push_back(e);
++route_id;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,10 +297,10 @@ const std::string TrajectoryServer::Implementation::parse_trajectories(
{
for (const auto& element : elements)
{
const auto& trajectory = element.route.trajectory();
const auto& trajectory = element.route->trajectory();

auto j_traj = _j_traj;
j_traj["map_name"] = element.route.map();
j_traj["map_name"] = element.route->map();
j_traj["robot_name"] = element.description.name();
j_traj["fleet_name"] = element.description.owner();
j_traj["id"] = element.participant;
Expand Down

0 comments on commit 297b02d

Please sign in to comment.