Skip to content

Commit

Permalink
Update configuration for the driver package
Browse files Browse the repository at this point in the history
  • Loading branch information
stefanscherzinger committed Apr 18, 2024
1 parent 033b287 commit e001873
Show file tree
Hide file tree
Showing 5 changed files with 151 additions and 46 deletions.
72 changes: 72 additions & 0 deletions schunk_egu_egk_gripper_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
cmake_minimum_required(VERSION 3.22)
project(schunk_egu_egk_gripper_driver)

# Set C++ standard to 17 if not set
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()

# Compiler-specific options
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# Find required packages
find_package(schunk_egu_egk_gripper_library REQUIRED)
find_package(schunk_egu_egk_gripper_interfaces REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(diagnostic_updater REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(control_msgs REQUIRED)
find_package(diagnostic_msgs REQUIRED)


#--------------------------------------------------------------------------------
# Build
#--------------------------------------------------------------------------------

add_library(${PROJECT_NAME} SHARED
src/schunk_gripper_wrapper.cpp
)
target_include_directories(${PROJECT_NAME} PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)
ament_target_dependencies(${PROJECT_NAME}
rclcpp
sensor_msgs
control_msgs
rclcpp_action
rclcpp_components
diagnostic_updater
diagnostic_msgs
schunk_egu_egk_gripper_interfaces
)
target_link_libraries(${PROJECT_NAME}
Schunk::schunk_egu_egk_gripper_library
)

#--------------------------------------------------------------------------------
# Install
#--------------------------------------------------------------------------------
install(TARGETS ${PROJECT_NAME}
DESTINATION lib/${PROJECT_NAME})

install(
DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
)

#--------------------------------------------------------------------------------
# Test
#--------------------------------------------------------------------------------
if(BUILD_TESTING)
endif()

# Ament package configuration
ament_package()

Empty file.
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,30 @@
#include "rclcpp_components/register_node_macro.hpp"
#include <rclcpp/parameter.hpp>
#include <rcl_interfaces/msg/parameter_event.hpp>
#include "schunk_gripper/schunk_gripper_lib.hpp"
#include "schunk_egu_egk_gripper_library/schunk_gripper_lib.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "control_msgs/action/gripper_command.hpp"
#include <diagnostic_updater/diagnostic_updater.hpp>

#include "schunk_gripper/action/grip_with_position.hpp"
#include "schunk_gripper/action/grip_with_velocity.hpp"
#include "schunk_gripper/action/grip_with_position_and_velocity.hpp"
#include "schunk_gripper/action/move_to_absolute_position.hpp"
#include "schunk_gripper/action/move_to_relative_position.hpp"
#include "schunk_gripper/msg/state.hpp"
#include "schunk_gripper/srv/acknowledge.hpp"
#include "schunk_gripper/srv/brake_test.hpp"
#include "schunk_gripper/srv/stop.hpp"
#include "schunk_gripper/srv/fast_stop.hpp"
#include "schunk_gripper/srv/prepare_for_shutdown.hpp"
#include "schunk_gripper/srv/softreset.hpp"
#include "schunk_gripper/action/release_workpiece.hpp"
#include "schunk_gripper/srv/release_for_manual_movement.hpp"
#include "schunk_gripper/srv/gripper_info.hpp"
#include "schunk_gripper/srv/change_ip.hpp"
#include "control_msgs/action/gripper_command.hpp"
#include "schunk_gripper/action/grip.hpp"
#include "schunk_gripper/srv/parameter_get.hpp"
#include "schunk_gripper/srv/parameter_set.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/grip_with_position.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/grip_with_velocity.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/grip_with_position_and_velocity.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/move_to_absolute_position.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/move_to_relative_position.hpp"
#include "schunk_egu_egk_gripper_interfaces/msg/state.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/acknowledge.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/brake_test.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/stop.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/fast_stop.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/prepare_for_shutdown.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/softreset.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/release_workpiece.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/release_for_manual_movement.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/gripper_info.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/change_ip.hpp"
#include "schunk_egu_egk_gripper_interfaces/action/grip.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/parameter_get.hpp"
#include "schunk_egu_egk_gripper_interfaces/srv/parameter_set.hpp"

extern std::map<std::string, const char*> param_inst;
extern std::map<std::string, std::string> inst_param;
Expand All @@ -39,26 +39,27 @@ class SchunkGripperNode : public rclcpp::Node, public Gripper
private:

std::mutex lock_service_post;

using Acknowledge = schunk_gripper::srv::Acknowledge;
using BrakeTest = schunk_gripper::srv::BrakeTest;
using Stop = schunk_gripper::srv::Stop;
using FastStop = schunk_gripper::srv::FastStop;
using ReleaseForManualMovement = schunk_gripper::srv::ReleaseForManualMovement;
using Softreset = schunk_gripper::srv::Softreset;
using PrepareForShutdown = schunk_gripper::srv::PrepareForShutdown;
using GripperInfo= schunk_gripper::srv::GripperInfo;
using ChangeIp = schunk_gripper::srv::ChangeIp;
using ParameterGet = schunk_gripper::srv::ParameterGet;
using ParameterSet = schunk_gripper::srv::ParameterSet;

using MoveToAbsolutePosition = schunk_gripper::action::MoveToAbsolutePosition;
using MoveToRelativePosition = schunk_gripper::action::MoveToRelativePosition;
using GripWithVelocity = schunk_gripper::action::GripWithVelocity;
using Grip = schunk_gripper::action::Grip;
using GripWithPositionAndVelocity = schunk_gripper::action::GripWithPositionAndVelocity;
using GripWithPosition = schunk_gripper::action::GripWithPosition;
using ReleaseWorkpiece = schunk_gripper::action::ReleaseWorkpiece;
using State = schunk_egu_egk_gripper_interfaces::msg::State;

using Acknowledge = schunk_egu_egk_gripper_interfaces::srv::Acknowledge;
using BrakeTest = schunk_egu_egk_gripper_interfaces::srv::BrakeTest;
using Stop = schunk_egu_egk_gripper_interfaces::srv::Stop;
using FastStop = schunk_egu_egk_gripper_interfaces::srv::FastStop;
using ReleaseForManualMovement = schunk_egu_egk_gripper_interfaces::srv::ReleaseForManualMovement;
using Softreset = schunk_egu_egk_gripper_interfaces::srv::Softreset;
using PrepareForShutdown = schunk_egu_egk_gripper_interfaces::srv::PrepareForShutdown;
using GripperInfo= schunk_egu_egk_gripper_interfaces::srv::GripperInfo;
using ChangeIp = schunk_egu_egk_gripper_interfaces::srv::ChangeIp;
using ParameterGet = schunk_egu_egk_gripper_interfaces::srv::ParameterGet;
using ParameterSet = schunk_egu_egk_gripper_interfaces::srv::ParameterSet;

using MoveToAbsolutePosition = schunk_egu_egk_gripper_interfaces::action::MoveToAbsolutePosition;
using MoveToRelativePosition = schunk_egu_egk_gripper_interfaces::action::MoveToRelativePosition;
using GripWithVelocity = schunk_egu_egk_gripper_interfaces::action::GripWithVelocity;
using Grip = schunk_egu_egk_gripper_interfaces::action::Grip;
using GripWithPositionAndVelocity = schunk_egu_egk_gripper_interfaces::action::GripWithPositionAndVelocity;
using GripWithPosition = schunk_egu_egk_gripper_interfaces::action::GripWithPosition;
using ReleaseWorkpiece = schunk_egu_egk_gripper_interfaces::action::ReleaseWorkpiece;
using GripperCommand = control_msgs::action::GripperCommand;

//Flags
Expand All @@ -70,11 +71,11 @@ class SchunkGripperNode : public rclcpp::Node, public Gripper
void publishState();

rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr jointStatePublisher;
rclcpp::Publisher<schunk_gripper::msg::State>::SharedPtr statePublisher;
rclcpp::Publisher<schunk_egu_egk_gripper_interfaces::msg::State>::SharedPtr statePublisher;
rclcpp::TimerBase::SharedPtr publish_state_timer;
rclcpp::TimerBase::SharedPtr publish_joint_timer;

schunk_gripper::msg::State msg;
schunk_egu_egk_gripper_interfaces::msg::State msg;
double state_frq;
double j_state_frq;
//Diagnostic updater
Expand Down Expand Up @@ -205,4 +206,4 @@ class SchunkGripperNode : public rclcpp::Node, public Gripper
rclcpp::Service<ChangeIp>::SharedPtr change_ip_service;
};

#endif
#endif
32 changes: 32 additions & 0 deletions schunk_egu_egk_gripper_driver/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<?xml version="1.0"?>
<package format="3">
<name>schunk_egu_egk_gripper_driver</name>
<version>1.0.0</version>
<description>ROS2 driver for Schunk's EGU/EGK grippers</description>
<author>Viktora Krimer</author>
<author>Fabian Reinwald</author>
<maintainer email="[email protected]">Stefan Scherzinger</maintainer>

<license>todo</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>schunk_egu_egk_gripper_library</depend>
<depend>schunk_egu_egk_gripper_interfaces</depend>
<depend>ament_index_cpp</depend>
<depend>diagnostic_updater</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_components</depend>
<depend>control_msgs</depend>
<depend>sensor_msgs</depend>

<exec_depend>ros2launch</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>

</package>


4 changes: 2 additions & 2 deletions schunk_egu_egk_gripper_driver/src/schunk_gripper_wrapper.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "schunk_gripper/schunk_gripper_wrapper.hpp"
#include "schunk_egu_egk_gripper_driver/schunk_gripper_wrapper.hpp"

std::map<std::string, const char*> param_inst =
{
Expand Down Expand Up @@ -168,7 +168,7 @@ void SchunkGripperNode::advertiseTopics()
{
//Advertise state
last_time = this->now(); //Initialize last_time
statePublisher = this->create_publisher<schunk_gripper::msg::State>("state", 1);
statePublisher = this->create_publisher<State>("state", 1);
publish_state_timer=this->create_wall_timer(std::chrono::duration<double>(1 / state_frq), std::bind(&SchunkGripperNode::publishState, this), messages_group);

//Initialize diagnostics
Expand Down

0 comments on commit e001873

Please sign in to comment.