diff --git a/iiwa_driver/CMakeLists.txt b/iiwa_driver/CMakeLists.txt index d7bf413..c98cdb8 100644 --- a/iiwa_driver/CMakeLists.txt +++ b/iiwa_driver/CMakeLists.txt @@ -31,6 +31,7 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") # Find catkin macros and libraries find_package(catkin REQUIRED COMPONENTS roscpp + message_generation rospy std_msgs geometry_msgs @@ -39,14 +40,26 @@ find_package(catkin REQUIRED COMPONENTS controller_manager sensor_msgs urdf + realtime_tools ) find_package(FRI REQUIRED COMPONENTS kuka_fri ) +# Message files +add_message_files( + FILES + AdditionalOutputs.msg +) + +generate_messages( + DEPENDENCIES + std_msgs +) + # Needed for ros packages -catkin_package(CATKIN_DEPENDS roscpp geometry_msgs tf std_msgs sensor_msgs hardware_interface controller_manager urdf) +catkin_package(CATKIN_DEPENDS roscpp message_runtime geometry_msgs tf std_msgs sensor_msgs hardware_interface controller_manager urdf realtime_tools) add_executable(iiwa_driver src/iiwa.cpp src/iiwa_driver.cpp) @@ -58,6 +71,8 @@ target_include_directories(iiwa_driver PUBLIC include ${catkin_INCLUDE_DIRS} ${F target_link_libraries(iiwa_driver ${catkin_LIBRARIES} ${FRI_LIBRARIES}) add_dependencies(iiwa_driver ${catkin_EXPORTED_TARGETS}) +add_dependencies(iiwa_driver iiwa_driver_generate_messages_cpp) + install(TARGETS iiwa_driver RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/iiwa_driver/include/iiwa_driver/iiwa.h b/iiwa_driver/include/iiwa_driver/iiwa.h index 629af95..3f828f4 100644 --- a/iiwa_driver/include/iiwa_driver/iiwa.h +++ b/iiwa_driver/include/iiwa_driver/iiwa.h @@ -29,6 +29,11 @@ #include #include +#include + +#include +#include + #include #include #include @@ -91,6 +96,9 @@ namespace iiwa_ros { void _publish(); void _on_fri_state_change(kuka::fri::ESessionState old_state, kuka::fri::ESessionState current_state) {} + // External torque publisher + realtime_tools::RealtimePublisher _additional_pub; + // Interfaces hardware_interface::JointStateInterface _joint_state_interface; hardware_interface::PositionJointInterface _position_joint_interface; diff --git a/iiwa_driver/msg/AdditionalOutputs.msg b/iiwa_driver/msg/AdditionalOutputs.msg new file mode 100644 index 0000000..fb2acec --- /dev/null +++ b/iiwa_driver/msg/AdditionalOutputs.msg @@ -0,0 +1,4 @@ +Header header +std_msgs/Float64MultiArray external_torques +std_msgs/Float64MultiArray commanded_torques +std_msgs/Float64MultiArray commanded_positions \ No newline at end of file diff --git a/iiwa_driver/package.xml b/iiwa_driver/package.xml index c360063..2cc0de0 100644 --- a/iiwa_driver/package.xml +++ b/iiwa_driver/package.xml @@ -43,6 +43,7 @@ catkin roscpp + message_generation rospy std_msgs controller_manager @@ -51,9 +52,10 @@ tf sensor_msgs urdf - + realtime_tools roscpp + message_runtime rospy std_msgs geometry_msgs @@ -62,7 +64,7 @@ tf sensor_msgs urdf - + realtime_tools diff --git a/iiwa_driver/src/iiwa.cpp b/iiwa_driver/src/iiwa.cpp index cb38853..571c9fb 100644 --- a/iiwa_driver/src/iiwa.cpp +++ b/iiwa_driver/src/iiwa.cpp @@ -186,6 +186,23 @@ namespace iiwa_ros { registerInterface(&_position_joint_interface); registerInterface(&_effort_joint_interface); registerInterface(&_velocity_joint_interface); + + _additional_pub.init(_nh, "additional_outputs", 20); + _additional_pub.msg_.external_torques.layout.dim.resize(1); + _additional_pub.msg_.external_torques.layout.data_offset = 0; + _additional_pub.msg_.external_torques.layout.dim[0].size = _num_joints; + _additional_pub.msg_.external_torques.layout.dim[0].stride = 0; + _additional_pub.msg_.external_torques.data.resize(_num_joints); + _additional_pub.msg_.commanded_torques.layout.dim.resize(1); + _additional_pub.msg_.commanded_torques.layout.data_offset = 0; + _additional_pub.msg_.commanded_torques.layout.dim[0].size = _num_joints; + _additional_pub.msg_.commanded_torques.layout.dim[0].stride = 0; + _additional_pub.msg_.commanded_torques.data.resize(_num_joints); + _additional_pub.msg_.commanded_positions.layout.dim.resize(1); + _additional_pub.msg_.commanded_positions.layout.data_offset = 0; + _additional_pub.msg_.commanded_positions.layout.dim[0].size = _num_joints; + _additional_pub.msg_.commanded_positions.layout.dim[0].stride = 0; + _additional_pub.msg_.commanded_positions.data.resize(_num_joints); } void Iiwa::_ctrl_loop() @@ -201,6 +218,17 @@ namespace iiwa_ros { _controller_manager->update(ros::Time::now(), elapsed_time); _write(elapsed_time); + // publish additional outputs + if (_additional_pub.trylock()) { + _additional_pub.msg_.header.stamp = ros::Time::now(); + for (unsigned i = 0; i < _num_joints; i++) { + _additional_pub.msg_.external_torques.data[i] = _robot_state.getExternalTorque()[i]; + _additional_pub.msg_.commanded_torques.data[i] = _robot_state.getCommandedTorque()[i]; + _additional_pub.msg_.commanded_positions.data[i] = _robot_state.getCommandedJointPosition()[i]; + } + _additional_pub.unlockAndPublish(); + } + _publish(); rate.sleep(); }