@ -67,12 +67,13 @@ def get_left_finger_state(joint_states):
return [ left_finger_position , left_finger_velocity , left_finger_effort ]
class HelloNode :
def __init__ ( self ) :
def __init__ ( self , robot_name = None ):
self . joint_states = None
self . point_cloud = None
self . tool = None
self . mode = None
self . dryrun = False
self . robot_name = robot_name
@classmethod
def quick_create ( cls , name , wait_for_first_pointcloud = False ) :
@ -231,30 +232,43 @@ class HelloNode:
self . node_name = rospy . get_name ( )
rospy . loginfo ( " {0} started " . format ( self . node_name ) )
self . trajectory_client = actionlib . SimpleActionClient ( ' /stretch_controller/follow_joint_trajectory ' , FollowJointTrajectoryAction )
if self . robot_name == None :
self . trajectory_client = actionlib . SimpleActionClient ( ' /stretch_controller/follow_joint_trajectory ' , FollowJointTrajectoryAction )
else :
self . trajectory_client = actionlib . SimpleActionClient ( ' / ' + self . robot_name + ' /follow_joint_trajectory ' , FollowJointTrajectoryAction )
server_reached = self . trajectory_client . wait_for_server ( timeout = rospy . Duration ( 60.0 ) )
if not server_reached :
rospy . signal_shutdown ( ' Unable to connect to arm action server. Timeout exceeded. ' )
sys . exit ( )
self . _joint_states_subscriber = rospy . Subscriber ( ' /stretch/joint_states ' , JointState , self . _joint_states_callback )
self . tf2_buffer = tf2_ros . Buffer ( )
self . tf2_listener = tf2_ros . TransformListener ( self . tf2_buffer )
if self . robot_name == None :
self . _joint_states_subscriber = rospy . Subscriber ( ' /stretch/joint_states ' , JointState , self . _joint_states_callback )
self . _tool_subscriber = rospy . Subscriber ( ' /tool ' , String , self . _tool_callback )
self . _mode_subscriber = rospy . Subscriber ( ' /mode ' , String , self . _mode_callback )
self . point_cloud_subscriber = rospy . Subscriber ( ' /camera/depth/color/points ' , PointCloud2 , self . _point_cloud_callback )
else :
self . _joint_states_subscriber = rospy . Subscriber ( ' / ' + self . robot_name + ' /joint_states ' , JointState , self . _joint_states_callback )
self . _tool_subscriber = rospy . Subscriber ( ' / ' + self . robot_name + ' /tool ' , String , self . _tool_callback )
self . _mode_subscriber = rospy . Subscriber ( ' / ' + self . robot_name + ' /mode ' , String , self . _mode_callback )
self . point_cloud_subscriber = rospy . Subscriber ( ' / ' + self . robot_name + ' /camera/depth/color/points ' , PointCloud2 , self . _point_cloud_callback )
self . _tool_subscriber = rospy . Subscriber ( ' /tool ' , String , self . _tool_callback )
self . _mode_subscriber = rospy . Subscriber ( ' /mode ' , String , self . _mode_callback )
self . point_cloud_subscriber = rospy . Subscriber ( ' /camera/depth/color/points ' , PointCloud2 , self . _point_cloud_callback )
self . point_cloud_pub = rospy . Publisher ( ' / ' + node_topic_namespace + ' /point_cloud2 ' , PointCloud2 , queue_size = 1 )
rospy . wait_for_service ( ' /home_the_robot ' )
rospy . wait_for_service ( ' /stow_the_robot ' )
rospy . wait_for_service ( ' /stop_the_robot ' )
rospy . loginfo ( ' Node ' + self . node_name + ' connected to robot services. ' )
self . home_the_robot_service = rospy . ServiceProxy ( ' /home_the_robot ' , Trigger )
self . stow_the_robot_service = rospy . ServiceProxy ( ' /stow_the_robot ' , Trigger )
self . stop_the_robot_service = rospy . ServiceProxy ( ' /stop_the_robot ' , Trigger )
if self . robot_name == None :
self . home_the_robot_service = rospy . ServiceProxy ( ' /home_the_robot ' , Trigger )
self . stow_the_robot_service = rospy . ServiceProxy ( ' /stow_the_robot ' , Trigger )
self . stop_the_robot_service = rospy . ServiceProxy ( ' /stop_the_robot ' , Trigger )
else :
self . home_the_robot_service = rospy . ServiceProxy ( ' / ' + self . robot_name + ' /home_the_robot ' , Trigger )
self . stow_the_robot_service = rospy . ServiceProxy ( ' / ' + self . robot_name + ' /stow_the_robot ' , Trigger )
self . stop_the_robot_service = rospy . ServiceProxy ( ' / ' + self . robot_name + ' /stop_the_robot ' , Trigger )
if wait_for_first_pointcloud :
# Do not start until a point cloud has been received