mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update
This commit is contained in:
parent
691215370a
commit
ea164a3acb
@ -24,16 +24,7 @@ def generate_launch_description():
|
|||||||
parameters=[joy_params, {'use_sim_time': use_sim_time}],
|
parameters=[joy_params, {'use_sim_time': use_sim_time}],
|
||||||
remappings=[('/cmd_vel','/cmd_vel_joy')]
|
remappings=[('/cmd_vel','/cmd_vel_joy')]
|
||||||
)
|
)
|
||||||
|
|
||||||
# twist_stamper = Node(
|
|
||||||
# package='twist_stamper',
|
|
||||||
# executable='twist_stamper',
|
|
||||||
# parameters=[{'use_sim_time': use_sim_time}],
|
|
||||||
# remappings=[('/cmd_vel_in','/diff_cont/cmd_vel_unstamped'),
|
|
||||||
# ('/cmd_vel_out','/diff_cont/cmd_vel')]
|
|
||||||
# )
|
|
||||||
|
|
||||||
|
|
||||||
return LaunchDescription([
|
return LaunchDescription([
|
||||||
DeclareLaunchArgument(
|
DeclareLaunchArgument(
|
||||||
'use_sim_time',
|
'use_sim_time',
|
||||||
@ -41,5 +32,4 @@ def generate_launch_description():
|
|||||||
description='Use sim time if true'),
|
description='Use sim time if true'),
|
||||||
joy_node,
|
joy_node,
|
||||||
teleop_node,
|
teleop_node,
|
||||||
# twist_stamper
|
|
||||||
])
|
])
|
23
launch/robot_controller.launch.py
Executable file
23
launch/robot_controller.launch.py
Executable file
@ -0,0 +1,23 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
use_sim_time = LaunchConfiguration('use_sim_time')
|
||||||
|
|
||||||
|
control_node = Node(
|
||||||
|
package='segwayrmp',
|
||||||
|
executable='SmartCar',
|
||||||
|
name='SmartCar',
|
||||||
|
remappings=[('/cmd_vel','/cmd_vel_out')]
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
'use_sim_time',
|
||||||
|
default_value='false',
|
||||||
|
description='Use sim time if true'),
|
||||||
|
control_node
|
||||||
|
])
|
135
launch/robot_joystick.launch.py
Normal file
135
launch/robot_joystick.launch.py
Normal file
@ -0,0 +1,135 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch.substitutions import LaunchConfiguration, Command, FindExecutable, PathJoinSubstitution
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
from launch_ros.descriptions import ParameterValue
|
||||||
|
from launch_ros.actions import LifecycleNode
|
||||||
|
|
||||||
|
import os
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
use_sim_time = LaunchConfiguration('use_sim_time')
|
||||||
|
|
||||||
|
joy_params = os.path.join(get_package_share_directory('cps_rmp220_support'),'config','joystick.yaml')
|
||||||
|
|
||||||
|
joy_node = Node(
|
||||||
|
package='joy',
|
||||||
|
executable='joy_node',
|
||||||
|
parameters=[joy_params, {'use_sim_time': use_sim_time}],
|
||||||
|
)
|
||||||
|
|
||||||
|
teleop_node = Node(
|
||||||
|
package='teleop_twist_joy',
|
||||||
|
executable='teleop_node',
|
||||||
|
name='teleop_node',
|
||||||
|
parameters=[joy_params, {'use_sim_time': use_sim_time}],
|
||||||
|
remappings=[('/cmd_vel','/cmd_vel_joy')]
|
||||||
|
)
|
||||||
|
|
||||||
|
twist_mux_params = os.path.join(get_package_share_directory('cps_rmp220_support'),'config','twist_mux.yaml')
|
||||||
|
twist_mux = Node(
|
||||||
|
package="twist_mux",
|
||||||
|
executable="twist_mux",
|
||||||
|
parameters=[twist_mux_params, {'use_sim_time': False}],
|
||||||
|
#remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')]
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
DeclareLaunchArgument(
|
||||||
|
'use_sim_time',
|
||||||
|
default_value='false',
|
||||||
|
description='Use sim time if true'),
|
||||||
|
joy_node,
|
||||||
|
teleop_node,
|
||||||
|
])
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
robot_description_content = Command(
|
||||||
|
[
|
||||||
|
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||||
|
" ",
|
||||||
|
PathJoinSubstitution(
|
||||||
|
[
|
||||||
|
FindPackageShare("bot_mini_description"),
|
||||||
|
"urdf",
|
||||||
|
"odrive_diffbot.urdf.xacro"
|
||||||
|
]
|
||||||
|
),
|
||||||
|
]
|
||||||
|
)
|
||||||
|
robot_description = {"robot_description": ParameterValue(robot_description_content, value_type=str)}
|
||||||
|
|
||||||
|
robot_controllers = PathJoinSubstitution(
|
||||||
|
[
|
||||||
|
FindPackageShare("bot_mini_bringup"),
|
||||||
|
"config",
|
||||||
|
"diffbot_controllers.yaml",
|
||||||
|
]
|
||||||
|
)
|
||||||
|
|
||||||
|
control_node = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="ros2_control_node",
|
||||||
|
parameters=[robot_description, robot_controllers],
|
||||||
|
output="both",
|
||||||
|
)
|
||||||
|
|
||||||
|
robot_state_pub_node = Node(
|
||||||
|
package="robot_state_publisher",
|
||||||
|
executable="robot_state_publisher",
|
||||||
|
output="both",
|
||||||
|
parameters=[robot_description],
|
||||||
|
)
|
||||||
|
|
||||||
|
joint_state_broadcaster_spawner = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["joint_state_broadcaster", "-c", "/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
robot_controller_spawner = Node(
|
||||||
|
package="controller_manager",
|
||||||
|
executable="spawner",
|
||||||
|
arguments=["diffbot_base_controller", "-c", "/controller_manager"],
|
||||||
|
)
|
||||||
|
|
||||||
|
joystick_spawner = Node(
|
||||||
|
package="joy",
|
||||||
|
executable="joy_node"
|
||||||
|
)
|
||||||
|
|
||||||
|
teleop_spawner = Node(
|
||||||
|
package="rmp220_teleop",
|
||||||
|
executable="rmp220_teleop",
|
||||||
|
remappings=[('/diffbot_base_controller/cmd_vel_unstamped','/cmd_vel_joy')]
|
||||||
|
)
|
||||||
|
|
||||||
|
cam_node = Node(
|
||||||
|
package="ros2_cam_openCV",
|
||||||
|
executable="cam_node"
|
||||||
|
)
|
||||||
|
|
||||||
|
lidar_dir = os.path.join(get_package_share_directory('lslidar_driver'), 'params', 'lsx10.yaml')
|
||||||
|
lidar_node = LifecycleNode(
|
||||||
|
package='lslidar_driver',
|
||||||
|
executable='lslidar_driver_node',
|
||||||
|
name='lslidar_driver_node',
|
||||||
|
output='screen',
|
||||||
|
emulate_tty=True,
|
||||||
|
namespace='',
|
||||||
|
parameters=[lidar_dir],
|
||||||
|
)
|
||||||
|
|
||||||
|
twist_mux_params = os.path.join(get_package_share_directory('bot_mini_bringup'),'config','twist_mux.yaml')
|
||||||
|
twist_mux = Node(
|
||||||
|
package="twist_mux",
|
||||||
|
executable="twist_mux",
|
||||||
|
parameters=[twist_mux_params, {'use_sim_time': False}],
|
||||||
|
remappings=[('/cmd_vel_out','/diffbot_base_controller/cmd_vel_unstamped')]
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
twist_mux
|
||||||
|
])
|
@ -7,14 +7,14 @@ def generate_launch_description():
|
|||||||
return LaunchDescription([
|
return LaunchDescription([
|
||||||
|
|
||||||
Node(
|
Node(
|
||||||
package='rplidar_ros',
|
package='sllidar_ros2',
|
||||||
executable='rplidar_composition',
|
executable='view_sllidar_launch',
|
||||||
output='screen',
|
output='screen',
|
||||||
parameters=[{
|
parameters=[{
|
||||||
'serial_port': '/dev/serial/by-path/platform-fd500000.pcie-pci-0000:01:00.0-usb-0:1.3:1.0-port0',
|
'serial_port': 'usb-Silicon_Labs_CP2102_USB_to_UART_Bridge_3453995662b3af4f81f4a69eba5f3f29-if00-port0',
|
||||||
'frame_id': 'laser_frame',
|
'frame_id': 'laser_frame',
|
||||||
'angle_compensate': True,
|
'angle_compensate': True,
|
||||||
'scan_mode': 'Standard'
|
'scan_mode': 'Sensitivity'
|
||||||
}]
|
}]
|
||||||
)
|
)
|
||||||
])
|
])
|
Loading…
Reference in New Issue
Block a user