diff --git a/crane_game_analyzer/include/crane_game_analyzer/kick_event_detector.hpp b/crane_game_analyzer/include/crane_game_analyzer/kick_event_detector.hpp index da4a171d0..93f145674 100644 --- a/crane_game_analyzer/include/crane_game_analyzer/kick_event_detector.hpp +++ b/crane_game_analyzer/include/crane_game_analyzer/kick_event_detector.hpp @@ -65,8 +65,6 @@ class KickEventDetector .fill("blue") .strokeWidth(2); visualizer->add(circle_builder.getSvgString()); - // visualizer->addCircle( - // world_model.getOurRobot(id)->pose.pos, 0.5, 2, "blue", "blue", 1.0, "KICK"); kick_event_origin.emplace(ros_clock.now(), world_model.ball.pos, RobotIdentifier{true, id}); } for (const auto & id : detected_bots.enemies) { @@ -77,8 +75,6 @@ class KickEventDetector .fill("blue") .strokeWidth(2); visualizer->add(circle_builder.getSvgString()); - // visualizer->addCircle( - // world_model.getTheirRobot(id)->pose.pos, 0.5, 2, "blue", "blue", 1.0, "KICK"); kick_event_origin.emplace(ros_clock.now(), world_model.ball.pos, RobotIdentifier{false, id}); } @@ -101,15 +97,7 @@ class KickEventDetector .stroke("red", 0.3) .strokeWidth(200); visualizer->add(line_builder.getSvgString()); - // visualizer->addTube( - // world_model.ball.pos, ongoing_kick_origin.value().position, - // 0.2, 2, "red", "", 1.0, "KICK"); } - - // キックの履歴を可視化 - // for (const auto & [kick_origin, kick_end] : kick_history) { - // visualizer->addLine(kick_origin.position, kick_end, 2, "red", 0.5, "KICK"); - // } } bool hasInterruptedOnGoingKick(const WorldModelWrapper & world_model) const diff --git a/crane_local_planner/include/crane_local_planner/simple_planner.hpp b/crane_local_planner/include/crane_local_planner/simple_planner.hpp index 6dc376ce1..331d7cca2 100644 --- a/crane_local_planner/include/crane_local_planner/simple_planner.hpp +++ b/crane_local_planner/include/crane_local_planner/simple_planner.hpp @@ -40,10 +40,6 @@ class SimplePlanner : public LocalPlannerBase for (auto & command : commands.robot_commands) { auto robot = world_model->getOurRobot(command.robot_id); if (not command.position_target_mode.empty()) { - // visualizer->addLine( - // robot->pose.pos.x(), robot->pose.pos.y(), - // command.position_target_mode.front().target_x, - // command.position_target_mode.front().target_y, 1); SvgLineBuilder line_builder; line_builder.start(robot->pose.pos) .end( diff --git a/crane_robot_skills/src/attacker.cpp b/crane_robot_skills/src/attacker.cpp index 04e419e0c..312e31755 100644 --- a/crane_robot_skills/src/attacker.cpp +++ b/crane_robot_skills/src/attacker.cpp @@ -110,7 +110,6 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base) }); addStateFunction(AttackerState::STEAL_BALL, [this]() -> Status { - // visualizer->addCircle(robot()->pose.pos, 0.25, 1, "blue", "white", 1.0); SvgCircleBuilder circle_builder; circle_builder.center(world_model()->ball.pos) .radius(0.25) @@ -278,7 +277,6 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base) auto our_robots = world_model()->ours.getAvailableRobots(robot()->id); const auto enemy_robots = world_model()->theirs.getAvailableRobots(); - // visualizer->addLine(world_model()->ball.pos, kick_target, 1, "red"); SvgLineBuilder line_builder; line_builder.start(world_model()->ball.pos).end(kick_target).stroke("red").strokeWidth(1); visualizer->add(line_builder.getSvgString()); diff --git a/crane_robot_skills/src/goal_kick.cpp b/crane_robot_skills/src/goal_kick.cpp index 3c8152d5d..aca3a4dd7 100644 --- a/crane_robot_skills/src/goal_kick.cpp +++ b/crane_robot_skills/src/goal_kick.cpp @@ -27,7 +27,6 @@ Status GoalKick::update() world_model()); Point target = world_model()->ball.pos + getNormVec(best_angle) * 0.5; - // visualizer->addLine(world_model()->ball.pos, target, 2, "red"); SvgLineBuilder line_builder; line_builder.start(world_model()->ball.pos).end(target).stroke("red").strokeWidth(2); visualizer->add(line_builder.getSvgString()); diff --git a/crane_robot_skills/src/goalie.cpp b/crane_robot_skills/src/goalie.cpp index 8caf1204f..19b85a5f4 100644 --- a/crane_robot_skills/src/goalie.cpp +++ b/crane_robot_skills/src/goalie.cpp @@ -49,7 +49,6 @@ Status Goalie::update() } } - // visualizer->addPoint(robot()->pose.pos.x(), robot()->pose.pos.y(), 0, "white", 1., phase); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(phase) @@ -87,7 +86,6 @@ void Goalie::emitBallFromPenaltyArea() } }(); - // visualizer->addLine(ball, pass_target, 1, "blue"); SvgLineBuilder line_builder; line_builder.start(ball).end(pass_target).stroke("blue").strokeWidth(1); visualizer->add(line_builder.getSvgString()); diff --git a/crane_robot_skills/src/kick.cpp b/crane_robot_skills/src/kick.cpp index 17d63120e..fe938ff41 100644 --- a/crane_robot_skills/src/kick.cpp +++ b/crane_robot_skills/src/kick.cpp @@ -35,7 +35,6 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) receive_skill->setParameter("redirect_kick_power", 0.3); addStateFunction(KickState::ENTRY_POINT, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::ENTRY_POINT"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("Kick::ENTRY_POINT") @@ -48,7 +47,6 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) addTransition(KickState::ENTRY_POINT, KickState::AROUND_BALL_AND_KICK, [this]() { return true; }); addStateFunction(KickState::POSITIVE_REDIRECT_KICK, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::POSITIVE_REDIRECT_KICK"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("Kick::POSITIVE_REDIRECT_KICK") @@ -89,7 +87,6 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) }); addStateFunction(KickState::REDIRECT_KICK, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::REDIRECT_KICK"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("Kick::REDIRECT_KICK") @@ -120,7 +117,6 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) addStateFunction(KickState::AROUND_BALL_AND_KICK, [this]() { auto target = getParameter("target"); Point ball_pos = world_model()->ball.pos; - // visualizer->addLine(ball_pos, ball_pos + (target - ball_pos).normalized() * 1.0, 1, "blue"); SvgLineBuilder line_builder; line_builder.start(ball_pos) .end(ball_pos + (target - ball_pos).normalized() * 1.0) @@ -128,14 +124,12 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) .strokeWidth(1); visualizer->add(line_builder.getSvgString()); constexpr double SWITCH_DISTANCE = 1.0; - // visualizer->addCircle(ball_pos, SWITCH_DISTANCE, 1, "yellow", "yellow", 0.); { SvgCircleBuilder circle_builder; circle_builder.center(ball_pos).radius(SWITCH_DISTANCE).stroke("yellow").strokeWidth(1); visualizer->add(circle_builder.getSvgString()); } if (robot()->getDistance(ball_pos) > SWITCH_DISTANCE) { - // visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::AROUND_BALL(遠い)"); { SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) @@ -149,7 +143,6 @@ Kick::Kick(RobotCommandWrapperBase::SharedPtr & base) .setTerminalVelocity(0.3); return Status::RUNNING; } else { - // visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::AROUND_BALL(近い)"); { SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) diff --git a/crane_robot_skills/src/marker.cpp b/crane_robot_skills/src/marker.cpp index 8d55e1ab7..ce08d9b05 100644 --- a/crane_robot_skills/src/marker.cpp +++ b/crane_robot_skills/src/marker.cpp @@ -38,12 +38,9 @@ Status Marker::update() } command.setTargetPosition(marking_point, 0.1).setTargetTheta(target_theta); - // visualizer->addCircle(enemy_pos, 0.3, 1, "black", ""); SvgCircleBuilder circle_builder; circle_builder.center(enemy_pos).radius(0.3).stroke("black").strokeWidth(1); visualizer->add(circle_builder.getSvgString()); - // visualizer->addLine( - // robot()->pose.pos, enemy_pos + (enemy_pos - robot()->pose.pos).normalized() * 0.3, 2, "black"); SvgLineBuilder line_builder; line_builder.start(robot()->pose.pos) .end(enemy_pos + (enemy_pos - robot()->pose.pos).normalized() * 0.3) diff --git a/crane_robot_skills/src/penalty_kick.cpp b/crane_robot_skills/src/penalty_kick.cpp index 78d28ed4c..59b4fca7b 100644 --- a/crane_robot_skills/src/penalty_kick.cpp +++ b/crane_robot_skills/src/penalty_kick.cpp @@ -46,7 +46,6 @@ PenaltyKick::PenaltyKick(RobotCommandWrapperBase::SharedPtr & base) double best_angle = GoalKick::getBestAngleToShootFromPoint( minimum_angle_accuracy, world_model()->ball.pos, world_model()); Point best_target = world_model()->ball.pos + getNormVec(best_angle) * 0.5; - // visualizer->addPoint(best_target.x(), best_target.y(), 1, "red", 1.0, "best_target"); SvgCircleBuilder circle_builder; circle_builder.center(best_target).radius(0.1).stroke("red").strokeWidth(1); diff --git a/crane_robot_skills/src/receive.cpp b/crane_robot_skills/src/receive.cpp index a41455831..488b3834d 100644 --- a/crane_robot_skills/src/receive.cpp +++ b/crane_robot_skills/src/receive.cpp @@ -48,7 +48,6 @@ Status Receive::update() }(); Point interception_point = getInterceptionPoint() + offset; - // visualizer->addLine(interception_point, robot()->pose.pos, 1, "red", 1., "intercept"); SvgLineBuilder line_builder; line_builder.start(interception_point).end(robot()->pose.pos).stroke("red").strokeWidth(1); visualizer->add(line_builder.getSvgString()); @@ -88,7 +87,6 @@ Point Receive::getInterceptionPoint() const Segment ball_line( world_model()->ball.pos, (world_model()->ball.pos + world_model()->ball.vel.normalized() * 10.0)); - // visualizer->addLine(ball_line.first, ball_line.second, 1, "blue", 1., "ball_line"); SvgLineBuilder line_builder; line_builder.start(ball_line.first).end(ball_line.second).stroke("blue").strokeWidth(1); visualizer->add(line_builder.getSvgString()); diff --git a/crane_robot_skills/src/single_ball_placement.cpp b/crane_robot_skills/src/single_ball_placement.cpp index 560ac3d17..fec6202f0 100644 --- a/crane_robot_skills/src/single_ball_placement.cpp +++ b/crane_robot_skills/src/single_ball_placement.cpp @@ -20,7 +20,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba setParameter("コート端判定のオフセット", 0.0); addStateFunction(SingleBallPlacementStates::ENTRY_POINT, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -47,7 +46,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba // 端にある場合、コート側からアプローチする addStateFunction(SingleBallPlacementStates::PULL_BACK_FROM_EDGE_PREPARE, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -107,7 +105,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba // PULL_BACK_FROM_EDGE_TOUCH addStateFunction(SingleBallPlacementStates::PULL_BACK_FROM_EDGE_TOUCH, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -169,7 +166,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba // PULL_BACK_FROM_EDGE_PULL addStateFunction(SingleBallPlacementStates::PULL_BACK_FROM_EDGE_PULL, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -200,7 +196,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba [this]() { return robot()->getDistance(world_model()->ball.pos) > 0.15; }); addStateFunction(SingleBallPlacementStates::GO_OVER_BALL, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -255,7 +250,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba [this]() { return skill_status == Status::SUCCESS; }); addStateFunction(SingleBallPlacementStates::CONTACT_BALL, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -279,7 +273,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba [this]() { return skill_status == Status::SUCCESS; }); addStateFunction(SingleBallPlacementStates::MOVE_TO_TARGET, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -319,7 +312,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba [this]() { return skill_status == Status::FAILURE; }); addStateFunction(SingleBallPlacementStates::SLEEP, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) @@ -346,7 +338,6 @@ SingleBallPlacement::SingleBallPlacement(RobotCommandWrapperBase::SharedPtr & ba }); addStateFunction(SingleBallPlacementStates::LEAVE_BALL, [this]() { - // visualizer->addPoint(robot()->pose.pos, 0, "white", 1.0, state_string); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text(state_string) diff --git a/crane_robot_skills/src/sub_attacker.cpp b/crane_robot_skills/src/sub_attacker.cpp index e3523a116..ac9669431 100644 --- a/crane_robot_skills/src/sub_attacker.cpp +++ b/crane_robot_skills/src/sub_attacker.cpp @@ -49,9 +49,6 @@ Status SubAttacker::update() result.closest_point + (robot()->pose.pos - result.closest_point).normalized() * 0.5); command.enableBallAvoidance(); { - // visualizer->addPoint( - // robot()->pose.pos.x(), robot()->pose.pos.y(), 0, - // "red", 1., "ボールラインから一旦遠ざかる"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("ボールラインから一旦遠ざかる") @@ -62,8 +59,6 @@ Status SubAttacker::update() } else { // ボールの進路上に移動 { - // visualizer->addPoint( - // robot()->pose.pos.x(), robot()->pose.pos.y(), 0, "red", 1., "ボールの進路上に移動"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("ボールの進路上に移動") @@ -89,8 +84,6 @@ Status SubAttacker::update() } } else { { - // visualizer->addPoint( - // robot()->pose.pos.x(), robot()->pose.pos.y(), 0, "red", 1., "ベストポジションへ移動"); SvgTextBuilder text_builder; text_builder.position(robot()->pose.pos.x() - 0.5, robot()->pose.pos.y() + 0.5) .text("ベストポジションへ移動") @@ -102,9 +95,6 @@ Status SubAttacker::update() double best_score = 0.0; for (const auto & dpps_point : dpps_points) { double score = getPointScore(dpps_point, world_model()->ball.pos, world_model()); - // visualizer->addPoint( - // dpps_point.x(), dpps_point.y(), std::clamp(static_cast(score * 100), 0, 20), "blue", - // 1.); if (score > best_score) { best_score = score; @@ -122,8 +112,6 @@ Status SubAttacker::update() auto to_goal = getNormVec(goal_angle); auto to_ball = (world_model()->ball.pos - target_pos).normalized(); { - // visualizer->addLine( - // target_pos, target_pos + to_goal * 3.0, 2, "yellow", 1.0, "Supporterシュートライン"); SvgLineBuilder line_builder; line_builder.start(target_pos).end(target_pos + to_goal * 3.0).stroke("yellow").strokeWidth(2); visualizer->add(line_builder.getSvgString()); diff --git a/crane_world_model_publisher/src/world_model_publisher.cpp b/crane_world_model_publisher/src/world_model_publisher.cpp index eb49d45c7..c6c99d389 100644 --- a/crane_world_model_publisher/src/world_model_publisher.cpp +++ b/crane_world_model_publisher/src/world_model_publisher.cpp @@ -447,7 +447,6 @@ void WorldModelPublisherComponent::publishWorldModel() Point p2; p1 << history.at(index).x, history.at(index).y; p2 << history.at(index + SAMPLING_NUM).x, history.at(index + SAMPLING_NUM).y; - // visualizer->addLine(p1, p2, 1, "yellow", index / static_cast(history.size())); SvgLineBuilder line_builder; line_builder.start(p1) .end(p2) @@ -465,7 +464,6 @@ void WorldModelPublisherComponent::publishWorldModel() Point p2; p1 << history.at(index).x, history.at(index).y; p2 << history.at(index + SAMPLING_NUM).x, history.at(index + SAMPLING_NUM).y; - // visualizer->addLine(p1, p2, 1, "blue", index / static_cast(history.size())); SvgLineBuilder line_builder; line_builder.start(p1) .end(p2) @@ -478,9 +476,6 @@ void WorldModelPublisherComponent::publishWorldModel() if (ball_history.size() > SAMPLING_NUM + 1) { for (int index = 0; index < ball_history.size() - SAMPLING_NUM; index += SAMPLING_NUM) { - // visualizer->addLine( - // ball_history.at(index), ball_history.at(index + SAMPLING_NUM), 1, "orange", - // index / static_cast(ball_history.size())); SvgLineBuilder line_builder; line_builder.start(ball_history.at(index)) .end(ball_history.at(index + SAMPLING_NUM)) diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/attacker_skill_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/attacker_skill_planner.hpp index 5f34bda97..d41b729a4 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/attacker_skill_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/attacker_skill_planner.hpp @@ -46,8 +46,6 @@ class AttackerSkillPlanner : public PlannerBase } else { std::string state_name(magic_enum::enum_name(skill->getCurrentState())); { - // visualizer->addCircle( - // skill->commander().getRobot()->pose.pos, 0.3, 2, "red", "", 1.0, state_name); SvgCircleBuilder circle_builder; circle_builder.center(skill->commander().getRobot()->pose.pos) .radius(0.3) @@ -57,11 +55,6 @@ class AttackerSkillPlanner : public PlannerBase } if (world_model->ball.isMoving()) { { - // visualizer->addLine( - // world_model->ball.pos, - // world_model->ball.pos + - // world_model->ball.vel.normalized() * world_model->getBallDistanceHorizon(), - // 3, "red", 0.5, ""); SvgLineBuilder line_builder; line_builder.start(world_model->ball.pos) .end( diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/offensive_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/offensive_planner.hpp index e0c91f1bb..b21559194 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/offensive_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/offensive_planner.hpp @@ -43,8 +43,6 @@ class OffensivePlanner : public PlannerBase { std::string state_name(magic_enum::enum_name(attacker->getCurrentState())); { - // visualizer->addCircle( - // attacker->commander().getRobot()->pose.pos, 0.3, 2, "red", "", 1.0, state_name); SvgCircleBuilder circle_builder; circle_builder.center(attacker->commander().getRobot()->pose.pos) .radius(0.3) @@ -53,11 +51,6 @@ class OffensivePlanner : public PlannerBase visualizer->add(circle_builder.getSvgString()); } { - // visualizer->addLine( - // world_model->ball.pos, - // world_model->ball.pos + - // world_model->ball.vel.normalized() * world_model->getBallDistanceHorizon(), - // 3, "red", 0.5, ""); SvgLineBuilder line_builder; line_builder.start(world_model->ball.pos) .end( diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/placement_avoidance_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/placement_avoidance_planner.hpp index 03f2c53f3..1a7ab04e2 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/placement_avoidance_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/placement_avoidance_planner.hpp @@ -95,7 +95,6 @@ class BallPlacementAvoidancePlanner : public PlannerBase // ボールプレイスメントエリアを横切ってしまうことがあるため、上書きしてしまう command.original_position = target_position; command.command->setTargetPosition(target_position); - // visualizer->addLine(command.original_position, target_position, 2, "yellow"); SvgLineBuilder line_builder; line_builder.start(command.original_position) .end(target_position) diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/simple_placer_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/simple_placer_planner.hpp index b081761a9..29f414251 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/simple_placer_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/simple_placer_planner.hpp @@ -189,7 +189,6 @@ class SimplePlacerPlanner : public PlannerBase // visualize areas with info for (const auto & area : areas_with_info) { - // visualizer->addRect(area.box, 1., "yellow", "", 1., area.name); SvgRectBuilder rect_builder; rect_builder.box(area.box).stroke("yellow").strokeWidth(1); visualizer->add(rect_builder.getSvgString()); @@ -203,9 +202,6 @@ class SimplePlacerPlanner : public PlannerBase } for (const auto & cmd : robot_commands) { - // visualizer->addLine( - // cmd.current_pose.x, cmd.current_pose.y, cmd.position_target_mode.front().target_x, - // cmd.position_target_mode.front().target_y, 1, "blue"); SvgLineBuilder line_builder; line_builder.start(cmd.current_pose.x, cmd.current_pose.y) .end(cmd.position_target_mode.front().target_x, cmd.position_target_mode.front().target_y)