Skip to content

Commit

Permalink
cxx: fixup compiler warnings (#148)
Browse files Browse the repository at this point in the history
- fixes Wreorder warnings
- use SYSTEM to import kortex_api, generated proto includes Wunused-parameter

This PR fixes all the simple compiler warnings.
One compiler warning renames: -Wunused-but-set-parameter in kortex_math_util.cpp
Left this one because it looks like a not implemented function.

This fixes #111

Signed-off-by: Alex Moriarty <alex.moriarty@picknik.ai>
  • Loading branch information
moriarty authored Jul 17, 2023
1 parent 617931d commit 680a22a
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
2 changes: 1 addition & 1 deletion kortex_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ target_include_directories(
)
ament_target_dependencies(
${PROJECT_NAME}
SYSTEM kortex_api
hardware_interface
kortex_api
pluginlib
rclcpp
)
Expand Down
14 changes: 7 additions & 7 deletions kortex_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,12 @@ KortexMultiInterfaceHardware::KortexMultiInterfaceHardware()
&transport_udp_realtime_,
[](k_api::KError err) { cout << "_________ callback error _________" << err.toString(); }},
session_manager_real_time_{&router_udp_realtime_},
k_api_twist_(nullptr),
base_{&router_tcp_},
base_cyclic_{&router_udp_realtime_},
gripper_motor_command_(nullptr),
gripper_command_max_velocity_(100.0),
gripper_command_max_force_(100.0),
servoing_mode_hw_(k_api::Base::ServoingModeInformation()),
joint_based_controller_running_(false),
twist_controller_running_(false),
Expand All @@ -69,11 +73,7 @@ KortexMultiInterfaceHardware::KortexMultiInterfaceHardware()
start_fault_controller_(false),
first_pass_(true),
gripper_joint_name_(""),
gripper_command_max_velocity_(100.0),
gripper_command_max_force_(100.0),
use_internal_bus_gripper_comm_(false),
k_api_twist_(nullptr),
gripper_motor_command_(nullptr)
use_internal_bus_gripper_comm_(false)
{
RCLCPP_INFO(LOGGER, "Setting severity threshold to DEBUG");
auto ret = rcutils_logging_set_logger_level(LOGGER.get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
Expand Down Expand Up @@ -743,7 +743,7 @@ CallbackReturn KortexMultiInterfaceHardware::on_deactivate(
}

return_type KortexMultiInterfaceHardware::read(
const rclcpp::Time & time, const rclcpp::Duration & period)
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
if (first_pass_)
{
Expand Down Expand Up @@ -799,7 +799,7 @@ void KortexMultiInterfaceHardware::readGripperPosition()
}

return_type KortexMultiInterfaceHardware::write(
const rclcpp::Time & time, const rclcpp::Duration & period)
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
if (block_write)
{
Expand Down

0 comments on commit 680a22a

Please sign in to comment.