Skip to content

Commit 680a22a

Browse files
authored
cxx: fixup compiler warnings (Kinovarobotics#148)
- 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 Kinovarobotics#111 Signed-off-by: Alex Moriarty <[email protected]>
1 parent 617931d commit 680a22a

File tree

2 files changed

+8
-8
lines changed

2 files changed

+8
-8
lines changed

kortex_driver/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,8 @@ target_include_directories(
3434
)
3535
ament_target_dependencies(
3636
${PROJECT_NAME}
37+
SYSTEM kortex_api
3738
hardware_interface
38-
kortex_api
3939
pluginlib
4040
rclcpp
4141
)

kortex_driver/src/hardware_interface.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,12 @@ KortexMultiInterfaceHardware::KortexMultiInterfaceHardware()
5252
&transport_udp_realtime_,
5353
[](k_api::KError err) { cout << "_________ callback error _________" << err.toString(); }},
5454
session_manager_real_time_{&router_udp_realtime_},
55+
k_api_twist_(nullptr),
5556
base_{&router_tcp_},
5657
base_cyclic_{&router_udp_realtime_},
58+
gripper_motor_command_(nullptr),
59+
gripper_command_max_velocity_(100.0),
60+
gripper_command_max_force_(100.0),
5761
servoing_mode_hw_(k_api::Base::ServoingModeInformation()),
5862
joint_based_controller_running_(false),
5963
twist_controller_running_(false),
@@ -69,11 +73,7 @@ KortexMultiInterfaceHardware::KortexMultiInterfaceHardware()
6973
start_fault_controller_(false),
7074
first_pass_(true),
7175
gripper_joint_name_(""),
72-
gripper_command_max_velocity_(100.0),
73-
gripper_command_max_force_(100.0),
74-
use_internal_bus_gripper_comm_(false),
75-
k_api_twist_(nullptr),
76-
gripper_motor_command_(nullptr)
76+
use_internal_bus_gripper_comm_(false)
7777
{
7878
RCLCPP_INFO(LOGGER, "Setting severity threshold to DEBUG");
7979
auto ret = rcutils_logging_set_logger_level(LOGGER.get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
@@ -743,7 +743,7 @@ CallbackReturn KortexMultiInterfaceHardware::on_deactivate(
743743
}
744744

745745
return_type KortexMultiInterfaceHardware::read(
746-
const rclcpp::Time & time, const rclcpp::Duration & period)
746+
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
747747
{
748748
if (first_pass_)
749749
{
@@ -799,7 +799,7 @@ void KortexMultiInterfaceHardware::readGripperPosition()
799799
}
800800

801801
return_type KortexMultiInterfaceHardware::write(
802-
const rclcpp::Time & time, const rclcpp::Duration & period)
802+
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
803803
{
804804
if (block_write)
805805
{

0 commit comments

Comments
 (0)