mock system working
This commit is contained in:
parent
3d098d19ab
commit
d0d759a787
@ -1,31 +1,3 @@
|
|||||||
# Copyright (c) 2022 PickNik, Inc.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions are met:
|
|
||||||
#
|
|
||||||
# * Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
#
|
|
||||||
# * Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in the
|
|
||||||
# documentation and/or other materials provided with the distribution.
|
|
||||||
#
|
|
||||||
# * Neither the name of the {copyright_holder} nor the names of its
|
|
||||||
# contributors may be used to endorse or promote products derived from
|
|
||||||
# this software without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
|
||||||
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
|
||||||
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
|
||||||
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
|
||||||
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
|
||||||
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
|
||||||
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
|
||||||
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
|
||||||
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
|
|
||||||
import launch
|
import launch
|
||||||
from launch.substitutions import (
|
from launch.substitutions import (
|
||||||
Command,
|
Command,
|
||||||
@ -37,8 +9,11 @@ from launch.conditions import IfCondition
|
|||||||
import launch_ros
|
import launch_ros
|
||||||
import os
|
import os
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
def generate_launch_description():
|
||||||
|
|
||||||
|
use_fake_hardware = 'true'
|
||||||
|
use_fake_hardware_bool = use_fake_hardware == 'true'
|
||||||
|
|
||||||
description_pkg_share = launch_ros.substitutions.FindPackageShare(
|
description_pkg_share = launch_ros.substitutions.FindPackageShare(
|
||||||
package="robotiq_description"
|
package="robotiq_description"
|
||||||
).find("robotiq_2f_description")
|
).find("robotiq_2f_description")
|
||||||
@ -124,25 +99,43 @@ def generate_launch_description():
|
|||||||
],
|
],
|
||||||
)
|
)
|
||||||
|
|
||||||
robotiq_gripper_controller_spawner = launch_ros.actions.Node(
|
|
||||||
package="controller_manager",
|
|
||||||
executable="spawner",
|
|
||||||
arguments=["robotiq_gripper_controller", "-c", "/controller_manager"],
|
|
||||||
)
|
|
||||||
|
|
||||||
robotiq_activation_controller_spawner = launch_ros.actions.Node(
|
robotiq_activation_controller_spawner = launch_ros.actions.Node(
|
||||||
package="controller_manager",
|
package="controller_manager",
|
||||||
executable="spawner",
|
executable="spawner",
|
||||||
arguments=["robotiq_activation_controller", "-c", "/controller_manager"],
|
arguments=["robotiq_activation_controller", "-c", "/controller_manager"],
|
||||||
)
|
)
|
||||||
|
|
||||||
|
def controller_spawner(name, active=True):
|
||||||
|
inactive_flags = ["--inactive"] if not active else []
|
||||||
|
return launch_ros.actions.Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=[
|
||||||
|
name,
|
||||||
|
"--controller-manager",
|
||||||
|
"/controller_manager",
|
||||||
|
] + inactive_flags,
|
||||||
|
)
|
||||||
|
|
||||||
|
if not use_fake_hardware_bool:
|
||||||
|
controller_spawner_names = ["robotiq_gripper_controller"]
|
||||||
|
controller_spawner_inactive_names = ["forward_gripper_position_controller",
|
||||||
|
"fake_gripper_controller"]
|
||||||
|
else:
|
||||||
|
controller_spawner_names = ["fake_gripper_controller"]
|
||||||
|
controller_spawner_inactive_names = ["forward_gripper_position_controller",
|
||||||
|
"robotiq_gripper_controller"]
|
||||||
|
|
||||||
|
controller_spawners = [controller_spawner(name) for name in controller_spawner_names] + [
|
||||||
|
controller_spawner(name, active=False) for name in controller_spawner_inactive_names
|
||||||
|
]
|
||||||
|
|
||||||
nodes = [
|
nodes = [
|
||||||
control_node,
|
control_node,
|
||||||
robot_state_publisher_node,
|
robot_state_publisher_node,
|
||||||
joint_state_broadcaster_spawner,
|
joint_state_broadcaster_spawner,
|
||||||
robotiq_gripper_controller_spawner,
|
|
||||||
robotiq_activation_controller_spawner,
|
robotiq_activation_controller_spawner,
|
||||||
rviz_node,
|
rviz_node,
|
||||||
]
|
] + controller_spawners
|
||||||
|
|
||||||
return launch.LaunchDescription(args + nodes)
|
return launch.LaunchDescription(args + nodes)
|
@ -14,7 +14,7 @@ def generate_launch_description():
|
|||||||
package="robotiq_2f_description"
|
package="robotiq_2f_description"
|
||||||
).find("robotiq_2f_description")
|
).find("robotiq_2f_description")
|
||||||
default_model_path = os.path.join(
|
default_model_path = os.path.join(
|
||||||
pkg_share, "urdf", "robotiq_2f_85.urdf.xacro"
|
pkg_share, "urdf", "robotiq_2f_140.urdf.xacro"
|
||||||
)
|
)
|
||||||
default_rviz_config_path = os.path.join(pkg_share, "rviz", "view_urdf.rviz")
|
default_rviz_config_path = os.path.join(pkg_share, "rviz", "view_urdf.rviz")
|
||||||
|
|
||||||
|
@ -18,11 +18,13 @@
|
|||||||
<ros2_control name="${name}" type="system">
|
<ros2_control name="${name}" type="system">
|
||||||
<!-- Plugins -->
|
<!-- Plugins -->
|
||||||
<hardware>
|
<hardware>
|
||||||
<plugin>robotiq_2f_interface/RobotiqGripperHardwareInterface</plugin>
|
|
||||||
<xacro:if value="${use_fake_hardware}">
|
<xacro:if value="${use_fake_hardware}">
|
||||||
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
|
<plugin>mock_components/GenericSystem</plugin>
|
||||||
|
<param name="mock_sensor_commands">${fake_sensor_commands}</param>
|
||||||
<param name="state_following_offset">0.0</param>
|
<param name="state_following_offset">0.0</param>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
<xacro:unless value="${use_fake_hardware}">
|
||||||
|
<plugin>robotiq_2f_interface/RobotiqGripperHardwareInterface</plugin>
|
||||||
<param name="gripper_closed_position">0.695</param>
|
<param name="gripper_closed_position">0.695</param>
|
||||||
<param name="robot_ip">${robot_ip}</param>
|
<param name="robot_ip">${robot_ip}</param>
|
||||||
<param name="robot_port">${robot_port}</param>
|
<param name="robot_port">${robot_port}</param>
|
||||||
@ -35,6 +37,7 @@
|
|||||||
<param name="max_speed">${max_speed}</param>
|
<param name="max_speed">${max_speed}</param>
|
||||||
<param name="min_force">${min_force}</param>
|
<param name="min_force">${min_force}</param>
|
||||||
<param name="max_force">${max_force}</param>
|
<param name="max_force">${max_force}</param>
|
||||||
|
</xacro:unless>
|
||||||
</hardware>
|
</hardware>
|
||||||
|
|
||||||
<!-- Joint interfaces -->
|
<!-- Joint interfaces -->
|
||||||
@ -47,7 +50,28 @@
|
|||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
</joint>
|
</joint>
|
||||||
<!-- When simulating we need to include the rest of the gripper joints -->
|
<!-- When simulating we need to include the rest of the gripper joints -->
|
||||||
<xacro:if value="false">
|
<xacro:if value="${use_fake_hardware}">
|
||||||
|
<joint name="${prefix}right_outer_knuckle_joint">
|
||||||
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
|
<param name="multiplier">-1</param>
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="${prefix}left_outer_finger_joint">
|
||||||
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
|
<param name="multiplier">1</param>
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
|
<joint name="${prefix}right_outer_finger_joint">
|
||||||
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
|
<param name="multiplier">-1</param>
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
<joint name="${prefix}left_inner_knuckle_joint">
|
<joint name="${prefix}left_inner_knuckle_joint">
|
||||||
<param name="mimic">${prefix}finger_joint</param>
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
<param name="multiplier">-1</param>
|
<param name="multiplier">-1</param>
|
||||||
@ -55,6 +79,13 @@
|
|||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
<joint name="${prefix}right_inner_knuckle_joint">
|
||||||
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
|
<param name="multiplier">-1</param>
|
||||||
|
<command_interface name="position"/>
|
||||||
|
<state_interface name="position"/>
|
||||||
|
<state_interface name="velocity"/>
|
||||||
|
</joint>
|
||||||
<joint name="${prefix}left_inner_finger_joint">
|
<joint name="${prefix}left_inner_finger_joint">
|
||||||
<param name="mimic">${prefix}finger_joint</param>
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
<param name="multiplier">1</param>
|
<param name="multiplier">1</param>
|
||||||
@ -62,22 +93,8 @@
|
|||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
<state_interface name="velocity"/>
|
<state_interface name="velocity"/>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name="${prefix}right_outer_knuckle_joint">
|
<joint name="${prefix}right_inner_finger_joint">
|
||||||
<param name="mimic">${prefix}finger_joint</param>
|
<param name="mimic">${prefix}finger_joint</param>
|
||||||
<param name="multiplier">-1</param>
|
|
||||||
<command_interface name="position"/>
|
|
||||||
<state_interface name="position"/>
|
|
||||||
<state_interface name="velocity"/>
|
|
||||||
</joint>
|
|
||||||
<joint name="${prefix}robotiq_140_left_finger_tip_joint">
|
|
||||||
<param name="mimic">${prefix}robotiq_140_left_knuckle_joint</param>
|
|
||||||
<param name="multiplier">-1</param>
|
|
||||||
<command_interface name="position"/>
|
|
||||||
<state_interface name="position"/>
|
|
||||||
<state_interface name="velocity"/>
|
|
||||||
</joint>
|
|
||||||
<joint name="${prefix}robotiq_140_right_finger_tip_joint">
|
|
||||||
<param name="mimic">${prefix}robotiq_140_left_knuckle_joint</param>
|
|
||||||
<param name="multiplier">1</param>
|
<param name="multiplier">1</param>
|
||||||
<command_interface name="position"/>
|
<command_interface name="position"/>
|
||||||
<state_interface name="position"/>
|
<state_interface name="position"/>
|
||||||
|
@ -220,8 +220,10 @@ hardware_interface::CallbackReturn RobotiqGripperHardwareInterface::on_activate(
|
|||||||
socket_adapter_->deactivate();
|
socket_adapter_->deactivate();
|
||||||
socket_adapter_->activate();
|
socket_adapter_->activate();
|
||||||
|
|
||||||
|
|
||||||
communication_thread_is_running_.store(true);
|
communication_thread_is_running_.store(true);
|
||||||
communication_thread_ = std::thread([this] { this->background_task(); });
|
communication_thread_ = std::thread([this] { this->background_task(); });
|
||||||
|
RCLCPP_INFO(logger_, "Background task thread started.");
|
||||||
}
|
}
|
||||||
catch (const std::exception& e)
|
catch (const std::exception& e)
|
||||||
{
|
{
|
||||||
@ -229,8 +231,14 @@ hardware_interface::CallbackReturn RobotiqGripperHardwareInterface::on_activate(
|
|||||||
return CallbackReturn::ERROR;
|
return CallbackReturn::ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!socket_adapter_->is_active()) {
|
||||||
|
RCLCPP_ERROR(logger_, "Attempted to activate while gripper is not active!");
|
||||||
|
return CallbackReturn::ERROR;
|
||||||
|
}
|
||||||
|
else{
|
||||||
RCLCPP_INFO(logger_, "Robotiq Gripper successfully activated!");
|
RCLCPP_INFO(logger_, "Robotiq Gripper successfully activated!");
|
||||||
return CallbackReturn::SUCCESS;
|
return CallbackReturn::SUCCESS;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
hardware_interface::CallbackReturn RobotiqGripperHardwareInterface::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
|
hardware_interface::CallbackReturn RobotiqGripperHardwareInterface::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/)
|
||||||
@ -312,7 +320,7 @@ std::vector<hardware_interface::CommandInterface> RobotiqGripperHardwareInterfac
|
|||||||
hardware_interface::CommandInterface("reactivate_gripper", "reactivate_gripper_response", &reactivate_gripper_response_));
|
hardware_interface::CommandInterface("reactivate_gripper", "reactivate_gripper_response", &reactivate_gripper_response_));
|
||||||
|
|
||||||
for (const auto& interface : command_interfaces) {
|
for (const auto& interface : command_interfaces) {
|
||||||
RCLCPP_DEBUG(logger_, "Exporting command interface for joint: %s type: %s",
|
RCLCPP_INFO(logger_, "Exporting command interface for joint: %s type: %s",
|
||||||
interface.get_name().c_str(), interface.get_interface_name().c_str());
|
interface.get_name().c_str(), interface.get_interface_name().c_str());
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -347,9 +355,17 @@ hardware_interface::return_type RobotiqGripperHardwareInterface::read(const rclc
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Process asynchronous reactivation response if available
|
// Process asynchronous reactivation response if available
|
||||||
if (reactivate_gripper_async_response_.load().has_value()) {
|
if (!std::isnan(reactivate_gripper_cmd_))
|
||||||
|
{
|
||||||
|
RCLCPP_INFO(logger_, "Sending gripper reactivation request.");
|
||||||
|
reactivate_gripper_async_cmd_.store(true);
|
||||||
|
reactivate_gripper_cmd_ = NO_NEW_CMD_;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (reactivate_gripper_async_response_.load().has_value())
|
||||||
|
{
|
||||||
reactivate_gripper_response_ = reactivate_gripper_async_response_.load().value();
|
reactivate_gripper_response_ = reactivate_gripper_async_response_.load().value();
|
||||||
reactivate_gripper_async_response_.store(std::nullopt); // Reset response
|
reactivate_gripper_async_response_.store(std::nullopt);
|
||||||
}
|
}
|
||||||
|
|
||||||
return hardware_interface::return_type::OK;
|
return hardware_interface::return_type::OK;
|
||||||
@ -381,19 +397,34 @@ void RobotiqGripperHardwareInterface::background_task()
|
|||||||
while (communication_thread_is_running_.load())
|
while (communication_thread_is_running_.load())
|
||||||
{
|
{
|
||||||
std::lock_guard<std::mutex> guard(resource_mutex_);
|
std::lock_guard<std::mutex> guard(resource_mutex_);
|
||||||
try
|
|
||||||
{
|
|
||||||
// Re-activate the gripper
|
|
||||||
// This can be used, for example, to re-run the auto-calibration.
|
|
||||||
if (reactivate_gripper_async_cmd_.load())
|
if (reactivate_gripper_async_cmd_.load())
|
||||||
{
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
// Execute the reactivation sequence
|
||||||
|
RCLCPP_INFO(logger_, "Reactivating gripper.");
|
||||||
socket_adapter_->deactivate();
|
socket_adapter_->deactivate();
|
||||||
socket_adapter_->activate();
|
socket_adapter_->activate(false);
|
||||||
reactivate_gripper_async_cmd_.store(false);
|
reactivate_gripper_async_cmd_.store(false); // Reset the command flag
|
||||||
reactivate_gripper_async_response_.store(true);
|
reactivate_gripper_async_response_.store(true); // Store the success of the operation
|
||||||
|
}
|
||||||
|
catch (const std::exception& e)
|
||||||
|
{
|
||||||
|
RCLCPP_ERROR(logger_, "Failed to reactivate gripper: %s", e.what());
|
||||||
|
reactivate_gripper_async_response_.store(false); // Store the failure of the operation
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write the latest command to the gripper.
|
// Additional periodic operations
|
||||||
|
performRegularOperations();
|
||||||
|
std::this_thread::sleep_for(gripperCommsLoopPeriod); // Sleep for the duration of the communication loop period
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void RobotiqGripperHardwareInterface::performRegularOperations()
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
int scaled_position = write_command_.load();
|
int scaled_position = write_command_.load();
|
||||||
int scaled_speed = write_speed_.load();
|
int scaled_speed = write_speed_.load();
|
||||||
int scaled_force = write_force_.load();
|
int scaled_force = write_force_.load();
|
||||||
@ -403,16 +434,12 @@ void RobotiqGripperHardwareInterface::background_task()
|
|||||||
throw std::runtime_error("Failed to send move command to Robotiq gripper.");
|
throw std::runtime_error("Failed to send move command to Robotiq gripper.");
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read the state of the gripper.
|
|
||||||
int raw_position = socket_adapter_->position();
|
int raw_position = socket_adapter_->position();
|
||||||
gripper_current_state_.store(convertRawToPosition(raw_position));
|
gripper_current_state_.store(convertRawToPosition(raw_position));
|
||||||
}
|
}
|
||||||
catch (const std::exception& e)
|
catch (const std::exception& e)
|
||||||
{
|
{
|
||||||
RCLCPP_ERROR(logger_, "Error in background task: %s", e.what());
|
RCLCPP_ERROR(logger_, "Regular operation error: %s", e.what());
|
||||||
}
|
|
||||||
|
|
||||||
std::this_thread::sleep_for(gripperCommsLoopPeriod); // Sleep for a predefined period
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -105,12 +105,17 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Roboti
|
|||||||
bool RobotiqActivationController::reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
|
bool RobotiqActivationController::reactivateGripper(std_srvs::srv::Trigger::Request::SharedPtr /*req*/,
|
||||||
std_srvs::srv::Trigger::Response::SharedPtr resp)
|
std_srvs::srv::Trigger::Response::SharedPtr resp)
|
||||||
{
|
{
|
||||||
|
RCLCPP_INFO(get_node()->get_logger(), "Received reactivation request.");
|
||||||
command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].set_value(ASYNC_WAITING);
|
command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].set_value(ASYNC_WAITING);
|
||||||
command_interfaces_[REACTIVATE_GRIPPER_CMD].set_value(1.0);
|
command_interfaces_[REACTIVATE_GRIPPER_CMD].set_value(1.0);
|
||||||
|
RCLCPP_INFO(get_node()->get_logger(), "Reactivation command sent to hardware interface.");
|
||||||
|
|
||||||
while (command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value() == ASYNC_WAITING)
|
int attempts = 0;
|
||||||
{
|
int max_attempts = 1000;
|
||||||
|
while (command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value() == ASYNC_WAITING && attempts < max_attempts) {
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
std::this_thread::sleep_for(std::chrono::milliseconds(50));
|
||||||
|
attempts++;
|
||||||
|
RCLCPP_INFO(get_node()->get_logger(), "Attempt %d: Checking response from hardware interface: %f", attempts, command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value());
|
||||||
}
|
}
|
||||||
resp->success = command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value();
|
resp->success = command_interfaces_[REACTIVATE_GRIPPER_RESPONSE].get_value();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user