12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
15
- #include " obstacle_stop_planner/ debug_marker.hpp"
15
+ #include " debug_marker.hpp"
16
16
17
17
#include < autoware/motion_utils/marker/marker_helper.hpp>
18
18
#include < autoware/universe_utils/geometry/geometry.hpp>
24
24
#include < tf2_geometry_msgs/tf2_geometry_msgs.hpp>
25
25
#endif
26
26
27
+ #include < limits>
27
28
#include < memory>
28
29
#include < vector>
29
30
@@ -38,7 +39,7 @@ using autoware::universe_utils::createMarkerColor;
38
39
using autoware::universe_utils::createMarkerScale;
39
40
using autoware::universe_utils::createPoint;
40
41
41
- namespace motion_planning
42
+ namespace autoware :: motion_planning
42
43
{
43
44
ObstacleStopPlannerDebugNode::ObstacleStopPlannerDebugNode (
44
45
rclcpp::Node * node, const double base_link2front)
@@ -458,39 +459,35 @@ MarkerArray ObstacleStopPlannerDebugNode::makeVisualizationMarker()
458
459
}
459
460
460
461
if (stop_obstacle_point_ptr_ != nullptr ) {
461
- auto marker = createDefaultMarker (
462
+ auto marker1 = createDefaultMarker (
462
463
" map" , current_time, " stop_obstacle_point" , 0 , Marker::SPHERE,
463
464
createMarkerScale (0.25 , 0.25 , 0.25 ), createMarkerColor (1.0 , 0.0 , 0.0 , 0.999 ));
464
- marker.pose .position = *stop_obstacle_point_ptr_;
465
- msg.markers .push_back (marker);
466
- }
465
+ marker1.pose .position = *stop_obstacle_point_ptr_;
466
+ msg.markers .push_back (marker1);
467
467
468
- if (stop_obstacle_point_ptr_ != nullptr ) {
469
- auto marker = createDefaultMarker (
468
+ auto marker2 = createDefaultMarker (
470
469
" map" , current_time, " stop_obstacle_text" , 0 , Marker::TEXT_VIEW_FACING,
471
470
createMarkerScale (0.0 , 0.0 , 1.0 ), createMarkerColor (1.0 , 1.0 , 1.0 , 0.999 ));
472
- marker .pose .position = *stop_obstacle_point_ptr_;
473
- marker .pose .position .z += 2.0 ;
474
- marker .text = " !" ;
475
- msg.markers .push_back (marker );
471
+ marker2 .pose .position = *stop_obstacle_point_ptr_;
472
+ marker2 .pose .position .z += 2.0 ;
473
+ marker2 .text = " !" ;
474
+ msg.markers .push_back (marker2 );
476
475
}
477
476
478
477
if (slow_down_obstacle_point_ptr_ != nullptr ) {
479
- auto marker = createDefaultMarker (
478
+ auto marker1 = createDefaultMarker (
480
479
" map" , current_time, " slow_down_obstacle_point" , 0 , Marker::SPHERE,
481
480
createMarkerScale (0.25 , 0.25 , 0.25 ), createMarkerColor (1.0 , 0.0 , 0.0 , 0.999 ));
482
- marker.pose .position = *slow_down_obstacle_point_ptr_;
483
- msg.markers .push_back (marker);
484
- }
481
+ marker1.pose .position = *slow_down_obstacle_point_ptr_;
482
+ msg.markers .push_back (marker1);
485
483
486
- if (slow_down_obstacle_point_ptr_ != nullptr ) {
487
- auto marker = createDefaultMarker (
484
+ auto marker2 = createDefaultMarker (
488
485
" map" , current_time, " slow_down_obstacle_text" , 0 , Marker::TEXT_VIEW_FACING,
489
486
createMarkerScale (0.0 , 0.0 , 1.0 ), createMarkerColor (1.0 , 1.0 , 1.0 , 0.999 ));
490
- marker .pose .position = *slow_down_obstacle_point_ptr_;
491
- marker .pose .position .z += 2.0 ;
492
- marker .text = " !" ;
493
- msg.markers .push_back (marker );
487
+ marker2 .pose .position = *slow_down_obstacle_point_ptr_;
488
+ marker2 .pose .position .z += 2.0 ;
489
+ marker2 .text = " !" ;
490
+ msg.markers .push_back (marker2 );
494
491
}
495
492
496
493
return msg;
@@ -542,4 +539,4 @@ VelocityFactorArray ObstacleStopPlannerDebugNode::makeVelocityFactorArray()
542
539
return velocity_factor_array;
543
540
}
544
541
545
- } // namespace motion_planning
542
+ } // namespace autoware:: motion_planning
0 commit comments