在joint sensor 包里加入一键启动脚本

This commit is contained in:
shenchenyang 2026-04-02 16:51:41 +08:00
parent ec52ded9aa
commit 470d94315f
4 changed files with 13 additions and 5 deletions

View File

@ -1,6 +1,6 @@
joint_sensor_node: joint_sensor_node:
ros__parameters: ros__parameters:
zero_offsets: [2.7995149378912956, 2.5233983960718795, 0.0, 0.0, 0.0, 0.0, 0.0] zero_offsets: [2.7995149378912956, 2.5233983960718795, 0.0, 0.0, 0.0, 0.0, 0.0]
sensor_directions: [-1.0, 1.0, -1.0, 1.0, 1.0, 1.0, 1.0] sensor_directions: [-1.0, 1.0, -1.0, -1.0, -1.0, 1.0, -1.0]
auto_zero_on_first_sample: true auto_zero_on_first_sample: true
can_interface: 'can2' can_interface: 'can2'

View File

@ -1,5 +1,5 @@
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument from launch.actions import DeclareLaunchArgument, TimerAction
from launch.substitutions import LaunchConfiguration from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory from ament_index_python.packages import get_package_share_directory
@ -28,7 +28,15 @@ def generate_launch_description():
parameters=[LaunchConfiguration('params_file')], parameters=[LaunchConfiguration('params_file')],
) )
joint_control_node = Node(
package='openarm_joint_sensor',
executable='joint_control',
name='joint_control_node',
output='screen',
)
delayed_joint_control_node = TimerAction(period=3.0, actions=[joint_control_node])
return LaunchDescription([ return LaunchDescription([
params_file_arg, params_file_arg,
joint_sensor_node, joint_sensor_node,
delayed_joint_control_node,
]) ])

View File

@ -109,7 +109,7 @@ class ProgressActionClient(Node):
def listener_callback(self, msg): def listener_callback(self, msg):
# self.send_goal([count, count1, 0.0, 0.0, 0.0, 0.0, 0.0]) # self.send_goal([count, count1, 0.0, 0.0, 0.0, 0.0, 0.0])
self.get_logger().info(f'Received joint states: {list(msg.name)} positions: {list(msg.position)}') # self.get_logger().info(f'Received joint states: {list(msg.name)} positions: {list(msg.position)}')
# Apply position filtering if enabled # Apply position filtering if enabled
arm_pos = list(msg.position) arm_pos = list(msg.position)
if self.enable_filter: if self.enable_filter:
@ -151,7 +151,7 @@ class ProgressActionClient(Node):
msg = Float64MultiArray() msg = Float64MultiArray()
msg.data = arm_pos msg.data = arm_pos
self.float64MultiArrayPublisher_.publish(msg) self.float64MultiArrayPublisher_.publish(msg)
self.get_logger().info(f'Published joint commands: {arm_pos}') self.get_logger().debug(f'Published joint commands: {arm_pos}')
def goal_response_callback(self, future): def goal_response_callback(self, future):
# 3-3.处理目标发送后的反馈; # 3-3.处理目标发送后的反馈;

View File

@ -22,7 +22,7 @@ class CallbackListener(can.Listener):
class JointSensorNode(Node): class JointSensorNode(Node):
def __init__(self): def __init__(self):
super().__init__('joint_sensor_node') super().__init__('joint_sensor_node')
self.declare_parameter('can_interface', 'can0') self.declare_parameter('can_interface', 'can2')
self.get_logger().info('正在初始化CAN接口...') self.get_logger().info('正在初始化CAN接口...')
can_interface = self.get_parameter('can_interface').value can_interface = self.get_parameter('can_interface').value
self.bus = can.interface.Bus(channel=can_interface, bustype='socketcan') self.bus = can.interface.Bus(channel=can_interface, bustype='socketcan')