Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Make new palm flesh the default palm for Hands E and G (lite) #844

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 6 additions & 6 deletions sr_error_reporter/src/UnderactuationErrorReporter.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/*
* Software License Agreement (BSD License)
* Copyright © 2021-2023 belongs to Shadow Robot Company Ltd.
* Copyright © 2021-2024 belongs to Shadow Robot Company Ltd.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
Expand Down Expand Up @@ -39,11 +39,6 @@
UnderactuationErrorReporter::UnderactuationErrorReporter(ros::NodeHandle& node_handle)
: node_handle_(node_handle)
{
trajectory_subscriber_left_ = node_handle.subscribe("/lh_trajectory_controller/state", 1,
&UnderactuationErrorReporter::trajectory_callback_left, this, ros::TransportHints().tcpNoDelay());
trajectory_subscriber_right_ = node_handle.subscribe("/rh_trajectory_controller/state", 1,
&UnderactuationErrorReporter::trajectory_callback_right, this, ros::TransportHints().tcpNoDelay());

if (!wait_for_param(node_handle, "robot_description"))
{
ROS_ERROR("UnderactuationErrorReporter did't find robot_description on parameter server");
Expand All @@ -58,6 +53,11 @@ UnderactuationErrorReporter::UnderactuationErrorReporter(ros::NodeHandle& node_h
{
ROS_ERROR("UnderactuationErrorReporter did't find robot_description_semantic on parameter server");
}

trajectory_subscriber_left_ = node_handle.subscribe("/lh_trajectory_controller/state", 1,
&UnderactuationErrorReporter::trajectory_callback_left, this, ros::TransportHints().tcpNoDelay());
trajectory_subscriber_right_ = node_handle.subscribe("/rh_trajectory_controller/state", 1,
niko-holmes marked this conversation as resolved.
Show resolved Hide resolved
&UnderactuationErrorReporter::trajectory_callback_right, this, ros::TransportHints().tcpNoDelay());
}

ros::Publisher UnderactuationErrorReporter::get_or_create_publisher(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python3

# Software License Agreement (BSD License)
# Copyright © 2019, 2022-2023 belongs to Shadow Robot Company Ltd.
# Copyright © 2019, 2022-2024 belongs to Shadow Robot Company Ltd.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without modification,
Expand Down Expand Up @@ -267,8 +267,7 @@ def test_waypoints(self):
wpose = waypoints[0]
waypoints.append(copy.deepcopy(wpose))

(plan3, fraction) = self.group.compute_cartesian_path(
waypoints, 0.01, 0.0)
(plan3, fraction) = self.group.compute_cartesian_path(waypoints, 0.01)
if not self._check_plan(plan3) and fraction > 0.8:
self.fail_list.append("Failed: test_waypoints, " + self.planner)
else:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python3

# Software License Agreement (BSD License)
# Copyright © 2019, 2022-2023 belongs to Shadow Robot Company Ltd.
# Copyright © 2019, 2022-2024 belongs to Shadow Robot Company Ltd.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without modification,
Expand Down Expand Up @@ -52,7 +52,6 @@ def __init__(self):
rospy.sleep(2)
group_id = rospy.get_param("~arm_group_name")
self.eef_step = rospy.get_param("~eef_step", 0.01)
self.jump_threshold = rospy.get_param("~jump_threshold", 1000)

self.group = MoveGroupCommander(group_id)
self._robot_name = self.robot._r.get_robot_name()
Expand Down Expand Up @@ -151,8 +150,7 @@ def plan_from_list(self, waypoint_names):
# +1 because current position is used as first waypiont.
rospy.logerr("Not all waypoints existed, not executing.")
return False
(plan, fraction) = self.group.compute_cartesian_path(
waypoints, self.eef_step, self.jump_threshold)
(plan, fraction) = self.group.compute_cartesian_path(waypoints, self.eef_step)

if fraction < self._min_wp_fraction:
rospy.logerr("Only managed to generate trajectory through" +
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python3

# Software License Agreement (BSD License)
# Copyright © 2015, 2022-2023 belongs to Shadow Robot Company Ltd.
# Copyright © 2015, 2022-2024 belongs to Shadow Robot Company Ltd.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without modification,
Expand Down Expand Up @@ -808,15 +808,13 @@ def run_joint_trajectory_unsafe(self, joint_trajectory, wait=True):
rospy.loginfo("Trajectory not completed")

def plan_to_waypoints_target(self, waypoints, reference_frame=None,
eef_step=0.005, jump_threshold=0.0, custom_start_state=None):
eef_step=0.005, custom_start_state=None):
"""
Specify a set of waypoints for the end-effector and plans.
This is a blocking method.
@param reference_frame - the reference frame in which the waypoints are given.
@param waypoints - an array of poses of end-effector.
@param eef_step - configurations are computed for every eef_step meters.
@param jump_threshold - maximum distance in configuration space between consecutive points in the
resulting path.
@param custom_start_state - specify a start state different than the current state.
@return - motion plan (RobotTrajectory msg) that contains the trajectory to the set wayapoints targets.
"""
Expand All @@ -827,7 +825,7 @@ def plan_to_waypoints_target(self, waypoints, reference_frame=None,
old_frame = self._move_group_commander.get_pose_reference_frame()
if reference_frame is not None:
self.set_pose_reference_frame(reference_frame)
self.__plan, fraction = self._move_group_commander.compute_cartesian_path(waypoints, eef_step, jump_threshold)
self.__plan, fraction = self._move_group_commander.compute_cartesian_path(waypoints, eef_step)
self.set_pose_reference_frame(old_frame)
return self.__plan, fraction

Expand Down
4 changes: 2 additions & 2 deletions sr_robot_launch/launch/sr_ur_arm_hand.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<!--
Software License Agreement (BSD License)
Copyright © 2022-2023 belongs to Shadow Robot Company Ltd.
Copyright © 2022-2024 belongs to Shadow Robot Company Ltd.
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -198,5 +198,5 @@
</group>

<!-- Publish underactuation error -->
<node name="error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>
<node name="underactuation_error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>
</launch>
4 changes: 2 additions & 2 deletions sr_robot_launch/launch/sr_ur_arms_hands.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<!--
Software License Agreement (BSD License)
Copyright © 2022-2023 belongs to Shadow Robot Company Ltd.
Copyright © 2022-2024 belongs to Shadow Robot Company Ltd.
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -217,6 +217,6 @@
</group>

<!-- Publish underactuation error -->
<node name="error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>
<node name="underactuation_error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>

</launch>
10 changes: 5 additions & 5 deletions sr_robot_launch/launch/srhand.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<!--
Software License Agreement (BSD License)
Copyright © 2022-2023 belongs to Shadow Robot Company Ltd.
Copyright © 2022-2024 belongs to Shadow Robot Company Ltd.
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
Expand Down Expand Up @@ -66,13 +66,13 @@
<arg if="$(eval arg('hand_id') == 'lh')" name="side" default="left"/>
<!-- Set to hand_e or hand_g -->
<arg name="hand_type" default="hand_e"/>
<arg if="$(eval arg('hand_type') == 'hand_e')" name="hand_version" default="E3M5"/>
<arg if="$(eval arg('hand_type') == 'hand_g')" name="hand_version" default="G1M5"/>
<arg if="$(eval arg('hand_type') == 'hand_e')" name="hand_version" default="E4"/>
<arg if="$(eval arg('hand_type') == 'hand_g')" name="hand_version" default="G4"/>
<arg if="$(eval arg('hand_type') == 'hand_c')" name="hand_version" default="C6M2"/>
<!-- Set to all allowed fingers by default but you can specify less using a list like this "th,ff,mf,rf,lf" -->
<arg name="fingers" default="all"/>
<!-- Set to pst sensors by default but they can be specified by finger using a list like this "th=pst,ff=pst,mf=pst,rf=pst,lf=pst" -->
<arg name="tip_sensors" default="pst"/>
<arg name="tip_sensors" default="mst"/>
<arg name="mid_sensors" default="none"/>
<arg name="prox_sensors" default="none"/>
<arg name="palm_sensor" default="none"/>
Expand Down Expand Up @@ -135,5 +135,5 @@
</include>

<!-- Publish underactuation error -->
<node name="error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>
<node name="underactuation_error_reporter" pkg="sr_error_reporter" type="error_reporter" output="screen"/>
</launch>