modify jz -> gripper
This commit is contained in:
@@ -6,13 +6,13 @@ from rclpy.node import Node
|
||||
from rclpy.action import ActionServer
|
||||
from rclpy.action import ActionServer
|
||||
from std_msgs.msg import String
|
||||
from interfaces.action import JzCmd
|
||||
from interfaces.action import GripperCmd
|
||||
import sys
|
||||
import os
|
||||
|
||||
class JzDevNode(Node):
|
||||
class GripperDevNode(Node):
|
||||
def __init__(self):
|
||||
super().__init__('jz_dev_node')
|
||||
super().__init__('gripper_dev_node')
|
||||
self.declare_parameter('port','/dev/ttyUSB0')
|
||||
param = self.get_parameter('port')
|
||||
self.com_dev = param.value
|
||||
@@ -20,12 +20,12 @@ class JzDevNode(Node):
|
||||
param = self.get_parameter('devid')
|
||||
self.devid = param.value
|
||||
|
||||
self.declare_parameter('name','/jz_cmd0')
|
||||
self.declare_parameter('name','/gripper_cmd0')
|
||||
param = self.get_parameter('name')
|
||||
self.srv_name = param.value
|
||||
print('param:',self.com_dev,self.devid,self.srv_name)
|
||||
self.get_logger().info(f'ros param:{self.com_dev},{self.devid},{self.srv_name}')
|
||||
self.action=ActionServer(self,JzCmd,self.srv_name,self.jz_cmd_callback_action)
|
||||
self.action=ActionServer(self,GripperCmd,self.srv_name,self.gripper_cmd_callback_action)
|
||||
|
||||
self.clawControl = RgClawControl()
|
||||
self.target_loc=0
|
||||
@@ -36,9 +36,9 @@ class JzDevNode(Node):
|
||||
self.cur_goal=None
|
||||
self.timer_on=False
|
||||
self.target_mode=0
|
||||
print('jz_dev_node init:',self.com_dev)
|
||||
print('gripper_dev_node init:',self.com_dev)
|
||||
#self.feedback_timer = self.create_timer(0.1, self.update_feedback)
|
||||
def jz_cmd_callback_action(self,goal):
|
||||
def gripper_cmd_callback_action(self,goal):
|
||||
self.cur_goal=goal
|
||||
req=goal.request
|
||||
self.target_loc=req.loc
|
||||
@@ -51,8 +51,8 @@ class JzDevNode(Node):
|
||||
ret = self.clawControl.enableClamp(self.devid, True)
|
||||
if ret!=1:
|
||||
print('enble fail!')
|
||||
result=JzCmd.Result()
|
||||
result.state="jz enable fail!"
|
||||
result=GripperCmd.Result()
|
||||
result.state="gripper enable fail!"
|
||||
result.result=0
|
||||
goal.abort()
|
||||
return result
|
||||
@@ -73,7 +73,7 @@ class JzDevNode(Node):
|
||||
else:
|
||||
loop_flag=abs(self.cur_loc-self.target_loc)>2 and abs(self.cur_loc-self.target_loc)>2
|
||||
#print('feedback:',self.cur_loc,speed,torque)
|
||||
feedback_msg = JzCmd.Feedback()
|
||||
feedback_msg = GripperCmd.Feedback()
|
||||
feedback_msg.loc=loc[0]
|
||||
feedback_msg.speed=speed[0]
|
||||
feedback_msg.torque=torque[0]
|
||||
@@ -81,7 +81,7 @@ class JzDevNode(Node):
|
||||
self.cur_goal.publish_feedback(feedback_msg)
|
||||
time.sleep(1)
|
||||
else:
|
||||
result=JzCmd.Result()
|
||||
result=GripperCmd.Result()
|
||||
result.state="uart open fail!"
|
||||
result.result=0
|
||||
goal.abort()
|
||||
@@ -90,31 +90,31 @@ class JzDevNode(Node):
|
||||
self.timer_on=True
|
||||
print('location diff:',self.cur_loc,self.target_loc)
|
||||
state = self.clawControl.getClampCurrentState(self.devid)
|
||||
result=JzCmd.Result()
|
||||
result=GripperCmd.Result()
|
||||
result.state=state[0]
|
||||
result.result=1
|
||||
goal.succeed()
|
||||
print('action finish',state)
|
||||
return result
|
||||
|
||||
def jz_cmd_callback(self, request, response):
|
||||
def gripper_cmd_callback(self, request, response):
|
||||
self.cur_loc=request.loc
|
||||
self.cur_speed=request.speed
|
||||
self.cur_torque=request.torque
|
||||
print('recv jz cmd:',self.cur_loc,self.cur_speed,self.cur_torque)
|
||||
print('recv gripper cmd:',self.cur_loc,self.cur_speed,self.cur_torque)
|
||||
flag = self.clawControl.serialOperation(self.com_dev, 115200, True)
|
||||
if flag == 1:
|
||||
#self.runCmd()
|
||||
#self.runCmd()
|
||||
response.state = self.clawControl.getClampCurrentState(devid)
|
||||
response.state = self.clawControl.getClampCurrentState(self.devid)
|
||||
self.clawControl.serialOperation(self.com_dev, 115200, False)
|
||||
print('send jz sta:',devid,response.state)
|
||||
print('send gripper sta:',self.devid,response.state)
|
||||
else:
|
||||
response.state = 'uart open failed'
|
||||
return response
|
||||
def main():
|
||||
rclpy.init()
|
||||
node=JzDevNode()
|
||||
node=GripperDevNode()
|
||||
rclpy.spin(node)
|
||||
rclpy.shutdown()
|
||||
pass
|
||||
7
gripper_dev/launch/gripper_dev.launch.py
Normal file
7
gripper_dev/launch/gripper_dev.launch.py
Normal file
@@ -0,0 +1,7 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
def generate_launch_description():
|
||||
return LaunchDescription([
|
||||
Node(package="gripper_dev",executable="gripper_dev_node",name="gripper_dev_node",
|
||||
parameters=[{'port':'/dev/ttyUSB0'}, {'name':'/gripper_cmd0'}, {'devid':6}])
|
||||
])
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>jz_dev</name>
|
||||
<name>gripper_dev</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="you@example.com">h</maintainer>
|
||||
4
gripper_dev/setup.cfg
Normal file
4
gripper_dev/setup.cfg
Normal file
@@ -0,0 +1,4 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/gripper_dev
|
||||
[install]
|
||||
install_scripts=$base/lib/gripper_dev
|
||||
@@ -1,15 +1,15 @@
|
||||
from setuptools import setup
|
||||
import os
|
||||
from glob import glob
|
||||
package_name='jz_dev'
|
||||
package_name='gripper_dev'
|
||||
setup(
|
||||
name='jz_dev',
|
||||
name='gripper_dev',
|
||||
version='0.1',
|
||||
description='A simple package for jz_dev',
|
||||
author='JZ Dev',
|
||||
author_email='jz_dev@example.com',
|
||||
url='https://github.com/jz_dev',
|
||||
packages=['jz_dev'],
|
||||
description='A simple package for gripper_dev',
|
||||
author='Gripper Dev',
|
||||
author_email='gripper_dev@example.com',
|
||||
url='https://github.com/gripper_dev',
|
||||
packages=['gripper_dev'],
|
||||
data_files=[
|
||||
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
|
||||
('share/' + package_name, ['package.xml']),
|
||||
@@ -19,6 +19,6 @@ setup(
|
||||
'setuptools',
|
||||
],
|
||||
entry_points={
|
||||
'console_scripts':['jz_dev_node = jz_dev.jz_dev_node:main']
|
||||
'console_scripts':['gripper_dev_node = gripper_dev.gripper_dev_node:main']
|
||||
}
|
||||
)
|
||||
@@ -8,9 +8,9 @@ def generate_launch_description():
|
||||
return LaunchDescription([
|
||||
# 启动orbbec_camera
|
||||
#ExecuteProcess(cmd=['ros2','launch', 'orbbec_camera', 'multi_camera.launch.py'],output='screen'),
|
||||
# ExecuteProcess(cmd=['ros2','launch', 'orbbec_camera', 'gemini_330_series.launch.py'],output='screen'),
|
||||
ExecuteProcess(cmd=['ros2','launch', 'orbbec_camera', 'gemini_330_series.launch.py'],output='screen'),
|
||||
# ExecuteProcess(cmd=['sleep', '2'],output='screen'),
|
||||
ExecuteProcess(cmd=['ros2','launch', 'realsense2_camera','rs_launch.py'],output='screen'),
|
||||
#ExecuteProcess(cmd=['ros2','launch', 'realsense2_camera','rs_launch.py'],output='screen'),
|
||||
|
||||
ExecuteProcess(cmd=['sleep', '2'],output='screen'),
|
||||
|
||||
|
||||
@@ -1,7 +0,0 @@
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
def generate_launch_description():
|
||||
return LaunchDescription([
|
||||
Node(package="jz_dev",executable="jz_dev_node",name="jz_dev_node",
|
||||
parameters=[{'port':'/dev/ttyUSB0'}, {'name':'/jz_cmd0'}, {'devid':9}])
|
||||
])
|
||||
@@ -1,4 +0,0 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/jz_dev
|
||||
[install]
|
||||
install_scripts=$base/lib/jz_dev
|
||||
Reference in New Issue
Block a user