Skip to content

Commit 2a8b9cf

Browse files
committed
ビルドエラー修正
1 parent b7cd045 commit 2a8b9cf

File tree

4 files changed

+6
-7
lines changed

4 files changed

+6
-7
lines changed

crane_local_planner/include/crane_local_planner/gridmap_planner.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,7 @@ class GridMapPlanner
119119
}
120120
Vector2 ball_vel_unit = world_model->ball.vel.normalized() * MAP_RESOLUTION;
121121
Point ball_pos = world_model->ball.pos;
122-
double time = 0.0;
122+
float time = 0.f;
123123
const double TIME_STEP = MAP_RESOLUTION / world_model->ball.vel.norm();
124124
map["ball_time"].setConstant(100.0);
125125
for (int i = 0; i < 100; ++i) {

crane_robot_receiver/src/robot_receiver_node.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -230,7 +230,7 @@ class RobotReceiverNode : public rclcpp::Node
230230
std::make_shared<MulticastReceiver>(config.ip, config.port));
231231
}
232232

233-
using std::chrono_literals::ms;
233+
using std::chrono::operator""ms;
234234
timer = create_wall_timer(10ms, [&]() {
235235
crane_msgs::msg::RobotFeedbackArray msg;
236236
for (auto & receiver : receivers) {

crane_world_model_publisher/src/world_model_publisher.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,7 @@ WorldModelPublisherComponent::WorldModelPublisherComponent(
2727
pub_world_model =
2828
create_publisher<crane_msgs::msg::WorldModel>("/world_model", 1);
2929

30-
using std::chrono_literals;
31-
30+
using std::chrono::operator""ms;
3231
timer = this->create_wall_timer(16ms, [this]() {
3332
if (has_vision_updated && has_geometry_updated) {
3433
publishWorldModel();

session/crane_session_controller/src/crane_session_controller.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ SessionControllerComponent::SessionControllerComponent(
2323
/*
2424
* 各セッションの設定の読み込み
2525
*/
26-
using std::filesystem : path;
26+
using std::filesystem::path;
2727
auto session_config_dir = path(ament_index_cpp::get_package_share_directory(
2828
"crane_session_controller")) /
2929
"config" / "play_situation";
@@ -56,7 +56,7 @@ SessionControllerComponent::SessionControllerComponent(
5656
};
5757

5858
std::cout << "----------------------------------------" << std::endl;
59-
using std::filesystem : directory_iterator;
59+
using std::filesystem::directory_iterator;
6060
for (auto & path : directory_iterator(session_config_dir)) {
6161
if (path.is_directory()) {
6262
for (auto & sub_path : directory_iterator(path.path())) {
@@ -114,7 +114,7 @@ SessionControllerComponent::SessionControllerComponent(
114114
}
115115
});
116116

117-
using std::chrono_literals;
117+
using std::chrono::operator""ms;
118118
timer = create_wall_timer(100ms, [&]() {
119119
auto it = event_map.find(play_situation.getSituationCommandText());
120120
if (it != event_map.end()) {

0 commit comments

Comments
 (0)