Skip to content

Commit

Permalink
Mess around with compiler flag settings
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe committed Aug 11, 2024
1 parent 979cc8b commit 3784166
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ jobs:
ROS_DISTRO: jazzy
env:
CXXFLAGS: >-
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls
-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-unknown-warning-option
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
DOCKER_IMAGE: moveit/moveit2:${{ matrix.env.IMAGE }}
UPSTREAM_WORKSPACE: >
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ int main(int argc, char* argv[])

std::chrono::seconds timeout_duration(3);
std::chrono::seconds time_elapsed(0);
auto start_time = std::chrono::steady_clock::now();
const auto start_time = std::chrono::steady_clock::now();

// create command queue to build trajectory message and add current robot state
std::deque<KinematicState> joint_cmd_rolling_window;
Expand All @@ -104,7 +104,7 @@ int main(int argc, char* argv[])
KinematicState joint_state = servo.getNextJointState(robot_state, joint_jog);
const StatusCode status = servo.getStatus();

auto current_time = std::chrono::steady_clock::now();
const auto current_time = std::chrono::steady_clock::now();
time_elapsed = std::chrono::duration_cast<std::chrono::seconds>(current_time - start_time);
if (time_elapsed > timeout_duration)
{
Expand Down
4 changes: 2 additions & 2 deletions moveit_ros/moveit_servo/demos/cpp_interface/demo_twist.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ int main(int argc, char* argv[])

std::chrono::seconds timeout_duration(4);
std::chrono::seconds time_elapsed(0);
auto start_time = std::chrono::steady_clock::now();
const auto start_time = std::chrono::steady_clock::now();

// create command queue to build trajectory message and add current robot state
std::deque<KinematicState> joint_cmd_rolling_window;
Expand All @@ -107,7 +107,7 @@ int main(int argc, char* argv[])
KinematicState joint_state = servo.getNextJointState(robot_state, target_twist);
const StatusCode status = servo.getStatus();

auto current_time = std::chrono::steady_clock::now();
const auto current_time = std::chrono::steady_clock::now();
time_elapsed = std::chrono::duration_cast<std::chrono::seconds>(current_time - start_time);
if (time_elapsed > timeout_duration)
{
Expand Down

0 comments on commit 3784166

Please sign in to comment.