diff --git a/config/diffbot_controllers.yaml b/config/diffbot_controllers.yaml index 17f680d..eba6cc9 100644 --- a/config/diffbot_controllers.yaml +++ b/config/diffbot_controllers.yaml @@ -41,7 +41,7 @@ diffbot_base_controller: open_loop: false #enable_odom_tf: true #disabled because tf will be handled by robot_localizaion node in the future (imu sensor fusion) - cmd_vel_timeout: 0.5 + cmd_vel_timeout: 0.1 #publish_limited_velocity: true use_stamped_vel: false velocity_rolling_window_size: 10 # changed from https://github.com/kallaspriit/rosbot/blob/main/ros/src/rosbot_description/config/diff_drive_controller.yaml diff --git a/launch/robot_controller.launch.py b/launch/robot_controller.launch.py index 3dbdbb3..a38dec4 100644 --- a/launch/robot_controller.launch.py +++ b/launch/robot_controller.launch.py @@ -72,39 +72,9 @@ def generate_launch_description(): arguments=["diffbot_base_controller", "-c", "/controller_manager"], ) - joystick_spawner = Node( - package="joy", - executable="joy_node" - ) - - teleop_spawner = Node( - package="rmp220_teleop", - executable="rmp220_teleop" - ) - - 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], - ) - return LaunchDescription([ control_node, robot_state_pub_node, - joint_state_broadcaster_spawner, #commented out because not needed? - robot_controller_spawner, - #joystick_spawner, - #teleop_spawner, - #cam_node, - #lidar_node + joint_state_broadcaster_spawner, + robot_controller_spawner ]) \ No newline at end of file diff --git a/launch/rsp.launch.py b/launch/rsp.launch.py index 4dbe3a5..172569f 100644 --- a/launch/rsp.launch.py +++ b/launch/rsp.launch.py @@ -38,21 +38,6 @@ def generate_launch_description(): ) 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", @@ -60,51 +45,6 @@ def generate_launch_description(): 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" - ) - - 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], - ) - return LaunchDescription([ - #control_node, - robot_state_pub_node, - #joint_state_broadcaster_spawner, - #robot_controller_spawner, - #joystick_spawner, - #teleop_spawner, - #cam_node, - #lidar_node + robot_state_pub_node ]) \ No newline at end of file