Skip to content

Commit

Permalink
remove unnecessary changes
Browse files Browse the repository at this point in the history
  • Loading branch information
MishkaMN committed Dec 15, 2023
1 parent 68a4a94 commit 481ec32
Show file tree
Hide file tree
Showing 13 changed files with 376 additions and 417 deletions.
8 changes: 4 additions & 4 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,9 @@
# Stage 1 - Acquire the CARMA source as well as any extra packages
# /////////////////////////////////////////////////////////////////////////////

FROM 63c52089ebf6 AS base-image
FROM usdotfhwastoldev/autoware.ai:develop AS base-image

FROM 63c52089ebf6 AS source-code
FROM base-image AS source-code

RUN mkdir ~/src
COPY --chown=carma . /home/carma/src/carma-platform/
Expand All @@ -46,7 +46,7 @@ RUN ~/src/carma-platform/docker/checkout.bash
# /////////////////////////////////////////////////////////////////////////////


FROM 63c52089ebf6 AS install
FROM base-image AS install
ARG ROS1_PACKAGES=""
ENV ROS1_PACKAGES=${ROS1_PACKAGES}
ARG ROS2_PACKAGES=""
Expand All @@ -63,7 +63,7 @@ RUN ~/carma_ws/src/carma-platform/docker/install.sh
# /////////////////////////////////////////////////////////////////////////////


FROM 63c52089ebf6
FROM base-image

ARG BUILD_DATE="NULL"
ARG VCS_REF="NULL"
Expand Down
8 changes: 4 additions & 4 deletions basic_autonomy/src/basic_autonomy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1305,14 +1305,14 @@ namespace basic_autonomy
const carma_ros2_utils::ClientPtr<carma_planning_msgs::srv::PlanTrajectory>& yield_client,
int yield_plugin_service_call_timeout)
{
RCLCPP_ERROR(node_handler->get_logger(), "Activate Object Avoidance");
RCLCPP_DEBUG(node_handler->get_logger(), "Activate Object Avoidance");

if (!yield_client || !yield_client->service_is_ready())
{
throw std::runtime_error("Yield Client is not set or unavailable after configuration state of lifecycle");
}

RCLCPP_ERROR(node_handler->get_logger(), "Yield Client is valid");
RCLCPP_DEBUG(node_handler->get_logger(), "Yield Client is valid");

auto yield_srv = std::make_shared<carma_planning_msgs::srv::PlanTrajectory::Request>();
yield_srv->initial_trajectory_plan = resp->trajectory_plan;
Expand All @@ -1330,11 +1330,11 @@ namespace basic_autonomy
return resp;
}

RCLCPP_ERROR(node_handler->get_logger(), "Received Traj from Yield");
RCLCPP_DEBUG(node_handler->get_logger(), "Received Traj from Yield");
carma_planning_msgs::msg::TrajectoryPlan yield_plan = yield_resp.get()->trajectory_plan;
if (is_valid_yield_plan(node_handler, yield_plan))
{
RCLCPP_ERROR(node_handler->get_logger(), "Yield trajectory validated");
RCLCPP_DEBUG(node_handler->get_logger(), "Yield trajectory validated");
resp->trajectory_plan = yield_plan;
}
else
Expand Down
4 changes: 2 additions & 2 deletions carma/launch/environment.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ def generate_launch_description():
("incoming_psm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_psm" ] ),
("incoming_bsm", [ EnvironmentVariable('CARMA_MSG_NS', default_value=''), "/incoming_bsm" ] ),
("georeference", [ EnvironmentVariable('CARMA_LOCZ_NS', default_value=''), "/map_param_loader/georeference" ] ),
#("external_objects", "fused_external_objects") TODO: directly listening to external objects
("external_objects", "fused_external_objects")
],
parameters=[
motion_computation_param_file,
Expand Down Expand Up @@ -529,6 +529,6 @@ def generate_launch_description():
carma_external_objects_container,
lanelet2_map_loader_container,
lanelet2_map_visualization_container,
#carma_cooperative_perception_container,
carma_cooperative_perception_container,
subsystem_controller
])
Loading

0 comments on commit 481ec32

Please sign in to comment.