Giter Club home page Giter Club logo

universal_robots_ros2_gazebo_simulation's Introduction

Universal_Robots_ROS2_Gazebo_Simulation

Example files and configurations for Gazebo Classic simulation of Universal Robots' manipulators.

Build status

Since Gazebo classic will not be supported from ROS 2 Jazzy on, this package is built against Humble and Iron only. The ros2 branch contains a version that is running on ROS Rolling on Ubuntu 22.04 at the time of writing. However, it is no longer supported.

Humble Iron
Branch humble iron
Build status Humble Binary Main
Iron Binary Main

A more detailed build status shows the state of all CI workflows inside this repo. Please note that the detailed view is intended for developers, while the one here should give end users an overview of the current released state.

Using the repository

Skip any of below steps is not applicable.

Setup ROS Workspace

  1. Create a colcon workspace:

    export COLCON_WS=~/workspaces/ur_gazebo
    mkdir -p $COLCON_WS/src
    

    NOTE: Feel free to change ~/workspaces/ur_gazebo to whatever absolute path you want.

    NOTE: Over time you will probably have multiple ROS workspaces, so it makes sense to them all in a subfolder. Also, it is good practice to put the ROS version in the name of the workspace, for different tests you could just add a suffix to the base name ur_gazebo.

  2. Download the required repositories and install package dependencies:

    cd $COLCON_WS/src
    git clone https://github.com/UniversalRobots/Universal_Robots_ROS2_Gazebo_Simulation.git
    rosdep update && rosdep install --ignore-src --from-paths . -y
    

Configure and Build Workspace:

To configure and build workspace execute following commands:

cd $COLCON_WS
colcon build --symlink-install

Running Simulation

ros2 launch ur_simulation_gazebo ur_sim_control.launch.py

Move robot using test script from ur_robot_driver package (if you've installed that one):

ros2 launch ur_robot_driver test_joint_trajectory_controller.launch.py

Example using MoveIt with simulated robot:

ros2 launch ur_simulation_gazebo ur_sim_moveit.launch.py

universal_robots_ros2_gazebo_simulation's People

Contributors

destogl avatar fmauch avatar mergify[bot] avatar relffok avatar urrsk avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

universal_robots_ros2_gazebo_simulation's Issues

Adding one package to the .repos file

It happened to me that rosdep install was failing since I hadn't installed the kinematics_interface package, I added it to the .repos and it worked smoothly. The concrete error I was receiving was:

ERROR: the following packages/stacks could not have their rosdep keys resolved
to system dependencies:
admittance_controller: Cannot locate rosdep definition for [kinematics_interface_kdl]

Hope it helps!
Cheers

multiple rviz gets launched while launching moveit

the issue is in this line

somehow the Ifcondition() is not taking in the value of the LaunchConfiguration. Maybe Open robotics changed something in the Python launch for Humble, which I might be unaware of.

As an alternate we need to use the LaunchContext to get the value of the LaunchConfiguration.

Hope this helps!

Controller Manager not available and empty Gazebo environment

I am trying to launch the simulation on ROS2 Iron on WSL (Ubuntu 22.04) on a Windows 10 device, but unfortunately I am getting the following errors that my controller manager is not available:
image

I tried to track down the problem and was looking at the node and topic lists while launching the simulation and this is what I gathered:
image

image

Therefore, I think that there is problem with publishing the controller manager, but I am unsure and don't really know how to implement a change...

I know that a similar issue was already closed #7 ,but the mentioned solution does not work for me:
image

Furthermore, because of this issue rviz is only semi-built, with the RobotModels status being an error:
image

And Gazebo is empty:
image

Any help would be appreciated, as I am still discovering ROS2 Iron and just installed WSL.

Force-Torque Sensor Simulation in Gazebo?

Ubuntu 22.04 | ROS: Humble | Gazebo Fortress | UR10e
I'm interested in simulating a UR10e including the EOA F/T sensor for compliance control testing.
Does this current package enable such a simulation?

It looks like previous versions of Gazebo could have leveraged something like this in the xacro:

(Found here)


100.0
ft_sensor_topic
schunk_wsg50_fixed_base_joint

But I'm having a hard time finding what the ros2 ft_sensor plugins for Fortress named. Any support and advice is appreciated.

Having trouble getting the scaled_joint_trajectory_controller to work with ur_sim_moveit.launch.py

Hi,

after finally being able to run the gazebo simulation (needed to update ur_msgs dependency like in #10, update the locale LC_NUMERIC which was related to MoveIt2) I am having difficulties with moving the gazebo ur robot.

Starting the driver using ros2 launch ur_simulation_gazebo ur_sim_moveit.launch.py starts the system with the following controllers loaded:

haavard@ThinkPad-X1:~/ros2_galactic_ws$ ros2 control list_controllers
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active    
joint_trajectory_controller[joint_trajectory_controller/JointTrajectoryController] active 

If I now move the ur robot using the Rviz with MoveIt, and hit Plan everything looks fine:

[move_group-7] [INFO] [1654174394.525417745] [moveit_move_group_default_capabilities.move_action_capability]: Received request
[move_group-7] [INFO] [1654174394.525607760] [moveit_move_group_default_capabilities.move_action_capability]: executing..
[move_group-7] [INFO] [1654174394.525716098] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[move_group-7] [INFO] [1654174394.525734318] [moveit_move_group_capabilities_base.move_group_capability]: Using planning pipeline 'move_group'
[move_group-7] [INFO] [1654174394.527467288] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[move_group-7] [INFO] [1654174394.544790690] [moveit_move_group_default_capabilities.move_action_capability]: Motion plan was computed successfully.

However, when I click Execute, this happens:

[move_group-7] [INFO] [1654174487.326601726] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Received goal request
[move_group-7] [INFO] [1654174487.326863641] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution request received
[move_group-7] [INFO] [1654174487.326926137] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-7] [INFO] [1654174487.326946210] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-7] [INFO] [1654174487.327084820] [moveit_ros.trajectory_execution_manager]: Validating trajectory with allowed_start_tolerance 0.01
[move_group-7] [INFO] [1654174487.327174635] [moveit_ros.trajectory_execution_manager]: Starting trajectory execution ...
[move_group-7] [INFO] [1654174487.327229781] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-7] [INFO] [1654174487.327245519] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-7] [ERROR] [1654174487.327394428] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Action client not connected to action server: scaled_joint_trajectory_controller/follow_joint_trajectory
[move_group-7] [ERROR] [1654174487.327397340] [moveit_ros.trajectory_execution_manager]: Failed to send trajectory part 1 of 1 to controller scaled_joint_trajectory_controller
[move_group-7] [INFO] [1654174487.327404627] [moveit_ros.trajectory_execution_manager]: Completed trajectory execution with status ABORTED ...
[move_group-7] [INFO] [1654174487.327496313] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution completed: ABORTED

Ok, so it looks like MoveIt wants to talk to the scaled_joint_trajectory_controller(SJTC), while it's actually joint_trajectory_controller (JTC) that's loaded by ros2 control. Fair enough, after switching the default controller in ur_moveit_config/config/controllers.yaml from the SJTC to JTC, I am able to move the gazebo robot!

Now, as an exercise, I looked into if I could manage to use the SJTC instead. First thing I tried is to unload JTC, and then load-configure-start the SJTC through ros2 control. This results in the following messages:

[gzserver-4] [INFO] [1654175946.435835764] [controller_manager]: Loading controller 'scaled_joint_trajectory_controller'
[gzserver-4] [INFO] [1654175946.453069320] [controller_manager]: Configuring controller 'scaled_joint_trajectory_controller'
[gzserver-4] [INFO] [1654175946.453128926] [scaled_joint_trajectory_controller]: Command interfaces are [position] and and state interfaces are [position velocity].
[gzserver-4] [INFO] [1654175946.453418972] [scaled_joint_trajectory_controller]: Controller state will be published at 100.00 Hz.
[gzserver-4] [INFO] [1654175946.453716297] [scaled_joint_trajectory_controller]: Action status changes will be monitored at 20.00 Hz.
[gzserver-4] [ERROR] [1654175971.846511008] [controller_manager]: Can't activate controller 'scaled_joint_trajectory_controller': State interface with key 'speed_scaling/speed_scaling_factor' does not exist

Based on these messages, the ros control architecture and the explanation of the different ur_controllers here I decided to try and start the speed_scaling_state_broadcaster instead of the joint_state_broadcaster hoping that these are equivalent besides that the former also publishes the required speed_scaling/speed_scaling_factor. Hope is not enough, as it didn't work...

I am at my limit of my ROS2 knowledge here, but I will continue to try. However, I am dropping this here to see if anyone knows how I can configure the UR robot to use the SJTC.

PS: I feel like using the ros2 control interface is the wrong thing to do here, as moveit adds a node called /moveit_simple_controller_manager which seems to invoke ros2 control, however I have not found a way to tell it to switch controllers. Looking into the moveit repo, it seems that there might be an implementation of a MoveItControllerManager that could help, but I am unable to see how I would approach incorporating it. It seems that this thread is relevant as well.

Thanks for any help, and sorry if this is inappropriate.

Universal Robot Model in Gazebo

Is it possible to spawn a Universal Robots model in Gazebo, like the UR5e?
I've got Ubuntu Desktop 22.04 LTS and ROS2 Humble.

Process has dies with error message

Hey, After the installation of simulation, and run codes os2 launch ur_simulation_gazebo ur_sim_control.launch.py, I have encountered with this error; [ERROR] [gzserver-4]: process has died [pid 8997, exit code -11, cmd 'gzserver -slibgazebo_ros_init.so -slibgazebo_ros_factory.so -slibgazebo_ros_force_system.so']
Is this because source folder cannot recognize urdf file? I have installed ROS2 Driver, Description with Binary builds, but installed Simulation repo with source build.
Thanks in advance.

Migrate to modern Gazebo

As you may know, Gazebo-classic (aka Gazebo11, see Terminology) is no longer being actively developed and will not be available on ROS Jazzy (REP 2000). I noticed that this project still uses Gazebo-classic. Are there any plans to migrate to modern Gazebo (previously known as Ignition)?

These might be helpful resources if you do plan to migrate:

Sometimes gazebo_ros2_control doesn't work

When I arranged src packages for different 3D Model instead of only UR robot. Sometimes gazebo_ros2_control is loaded and worked, some of time gazebo_ros2_control doesnt spawn and not work. It probably works unstable for loading the heavy 3D Model. What do you think about adding delay inside ur_sim_control.launch.py and ur_sim_moveit.launch.py ?

[INFO] [move_group-1]: process started with pid [123764]
[INFO] [rviz2-2]: process started with pid [123766]
[INFO] [servo_node_main-3]: process started with pid [123768]
[INFO] [robot_state_publisher-4]: process started with pid [123770]
[INFO] [spawner-5]: process started with pid [123772]
[INFO] [spawner-6]: process started with pid [123774]
[INFO] [gzserver-7]: process started with pid [123776]
[INFO] [gzclient-8]: process started with pid [123778]
[INFO] [spawn_entity.py-9]: process started with pid [123782]
[robot_state_publisher-4] [INFO] [1715871119.685552372] [robot_state_publisher]: got segment base
[robot_state_publisher-4] [INFO] [1715871119.685662482] [robot_state_publisher]: got segment base_link
[robot_state_publisher-4] [INFO] [1715871119.685675017] [robot_state_publisher]: got segment base_link_inertia
[robot_state_publisher-4] [INFO] [1715871119.685679826] [robot_state_publisher]: got segment camera_link
[robot_state_publisher-4] [INFO] [1715871119.685689078] [robot_state_publisher]: got segment cell
[robot_state_publisher-4] [INFO] [1715871119.685697683] [robot_state_publisher]: got segment flange
[robot_state_publisher-4] [INFO] [1715871119.685702116] [robot_state_publisher]: got segment forearm_link
[robot_state_publisher-4] [INFO] [1715871119.685706514] [robot_state_publisher]: got segment ft_frame
[robot_state_publisher-4] [INFO] [1715871119.685710657] [robot_state_publisher]: got segment shoulder_link
[robot_state_publisher-4] [INFO] [1715871119.685714858] [robot_state_publisher]: got segment tool0
[robot_state_publisher-4] [INFO] [1715871119.685719114] [robot_state_publisher]: got segment upper_arm_link
[robot_state_publisher-4] [INFO] [1715871119.685723565] [robot_state_publisher]: got segment world
[robot_state_publisher-4] [INFO] [1715871119.685727842] [robot_state_publisher]: got segment wrist_1_link
[robot_state_publisher-4] [INFO] [1715871119.685731925] [robot_state_publisher]: got segment wrist_2_link
[robot_state_publisher-4] [INFO] [1715871119.685736187] [robot_state_publisher]: got segment wrist_3_link
[move_group-1] [INFO] [1715871119.699676872] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0 seconds
[move_group-1] [INFO] [1715871119.699731215] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[move_group-1] [INFO] [1715871119.699741641] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed jointAssuming fixed joint
[move_group-1] [WARN] [1715871119.796543625] [moveit_robot_model.robot_model]: Link cell has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[move_group-1] [WARN] [1715871119.797443643] [moveit_robot_model.robot_model]: Link comau has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[move_group-1] [WARN] [1715871119.797978652] [moveit_robot_model.robot_model]: Group 'camera' must have at least one valid joint
[move_group-1] [WARN] [1715871119.798302963] [moveit_robot_model.robot_model]: Failed to add group 'camera'
[servo_node_main-3] [WARN] [1715871119.841634489] [moveit_robot_model.robot_model]: Link cell has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[servo_node_main-3] [WARN] [1715871119.841788778] [moveit_robot_model.robot_model]: Group 'camera' must have at least one valid joint
[servo_node_main-3] [WARN] [1715871119.841795550] [moveit_robot_model.robot_model]: Failed to add group 'camera'
[servo_node_main-3] [WARN] [1715871119.845223229] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[move_group-1] [INFO] [1715871120.059075056] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[move_group-1] [INFO] [1715871120.059197390] [moveit.ros_planning_interface.moveit_cpp]: Listening to 'joint_states' for joint states
[move_group-1] [INFO] [1715871120.059733864] [moveit_ros.current_state_monitor]: Listening to joint states on topic 'joint_states'
[move_group-1] [INFO] [1715871120.060046243] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[move_group-1] [INFO] [1715871120.060056458] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[move_group-1] [INFO] [1715871120.060302889] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene'
[move_group-1] [INFO] [1715871120.060312194] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[move_group-1] [INFO] [1715871120.060565244] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'collision_object'
[move_group-1] [INFO] [1715871120.060858817] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry
[move_group-1] [WARN] [1715871120.061022674] [moveit.ros.occupancy_map_monitor.middleware_handle]: Resolution not specified for Octomap. Assuming resolution = 0.1 instead
[move_group-1] [ERROR] [1715871120.061036422] [moveit.ros.occupancy_map_monitor.middleware_handle]: No 3D sensor plugin(s) defined for octomap updates
[spawn_entity.py-9] [INFO] [1715871120.066031426] [spawn_ur]: Spawn Entity started
[spawn_entity.py-9] [INFO] [1715871120.066293950] [spawn_ur]: Loading entity published on topic robot_description
[spawn_entity.py-9] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[spawn_entity.py-9] warnings.warn(
[spawn_entity.py-9] [INFO] [1715871120.067861486] [spawn_ur]: Waiting for entity xml on robot_description
[spawn_entity.py-9] [INFO] [1715871120.078953207] [spawn_ur]: Waiting for service /spawn_entity, timeout = 30
[spawn_entity.py-9] [INFO] [1715871120.079222580] [spawn_ur]: Waiting for service /spawn_entity
[servo_node_main-3] [INFO] [1715871120.083904369] [moveit_ros.current_state_monitor]: Listening to joint states on topic '/joint_states'
[servo_node_main-3] [INFO] [1715871120.086693454] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[servo_node_main-3] [INFO] [1715871120.086709289] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[servo_node_main-3] [INFO] [1715871120.087394436] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene'
[servo_node_main-3] [INFO] [1715871120.087653976] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on '/servo_node/publish_planning_scene'
[servo_node_main-3] [WARN] [1715871120.092220183] [moveit_servo.servo_calcs]: No kinematics solver instantiated for group 'ur_manipulator'. Will use inverse Jacobian for servo calculations instead.
[servo_node_main-3] [WARN] [1715871120.092237433] [moveit_servo.collision_check]: Collision check rate is low, increase it in yaml file if CPU allows
[move_group-1] [INFO] [1715871120.469873486] [moveit.ros_planning_interface.moveit_cpp]: Loading planning pipeline 'pilz_industrial_motion_planner'
[move_group-1] [INFO] [1715871120.471352581] [moveit.pilz_industrial_motion_planner.joint_limits_aggregator]: Reading limits from namespace robot_description_planning
[move_group-1] [INFO] [1715871120.473983873] [moveit.pilz_industrial_motion_planner]: Available plugins: pilz_industrial_motion_planner/PlanningContextLoaderCIRC pilz_industrial_motion_planner/PlanningContextLoaderLIN pilz_industrial_motion_planner/PlanningContextLoaderPTP
[move_group-1] [INFO] [1715871120.473998258] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderCIRC
[move_group-1] [INFO] [1715871120.474756740] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [CIRC]
[move_group-1] [INFO] [1715871120.474765963] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderLIN
[move_group-1] [INFO] [1715871120.475218334] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [LIN]
[move_group-1] [INFO] [1715871120.475225470] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderPTP
[move_group-1] [INFO] [1715871120.475678649] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [PTP]
[move_group-1] [INFO] [1715871120.475687356] [moveit.ros_planning.planning_pipeline]: Using planning interface 'Pilz Industrial Motion Planner'
[move_group-1] [INFO] [1715871120.476950803] [moveit_ros.fix_workspace_bounds]: Param 'pilz_industrial_motion_planner.default_workspace_bounds' was not set. Using default value: 10.000000
[move_group-1] [INFO] [1715871120.476965722] [moveit_ros.fix_start_state_bounds]: Param 'pilz_industrial_motion_planner.start_state_max_bounds_error' was not set. Using default value: 0.050000
[move_group-1] [INFO] [1715871120.476998444] [moveit_ros.fix_start_state_bounds]: Param 'pilz_industrial_motion_planner.start_state_max_dt' was not set. Using default value: 0.500000
[move_group-1] [INFO] [1715871120.477007932] [moveit_ros.fix_start_state_collision]: Param 'pilz_industrial_motion_planner.start_state_max_dt' was not set. Using default value: 0.500000
[move_group-1] [INFO] [1715871120.477011069] [moveit_ros.fix_start_state_collision]: Param 'pilz_industrial_motion_planner.jiggle_fraction' was not set. Using default value: 0.020000
[move_group-1] [INFO] [1715871120.477014621] [moveit_ros.fix_start_state_collision]: Param 'pilz_industrial_motion_planner.max_sampling_attempts' was not set. Using default value: 100
[move_group-1] [INFO] [1715871120.477022677] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Workspace Bounds'
[move_group-1] [INFO] [1715871120.477025399] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Bounds'
[move_group-1] [INFO] [1715871120.477027645] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State In Collision'
[move_group-1] [INFO] [1715871120.477029902] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Path Constraints'
[move_group-1] [INFO] [1715871120.487631753] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for scaled_joint_trajectory_controller
[move_group-1] [INFO] [1715871120.488556404] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for joint_trajectory_controller
[move_group-1] [INFO] [1715871120.488652983] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1715871120.488667451] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1715871120.488869447] [moveit_ros.trajectory_execution_manager]: Trajectory execution is not managing controllers
[move_group-1] [INFO] [1715871120.488880442] [move_group.move_group]: MoveGroup debug mode is ON
[move_group-1] [INFO] [1715871120.496408670] [move_group.move_group]:
[move_group-1]
[move_group-1] ********************************************************
[move_group-1] * MoveGroup using:
[move_group-1] * - ApplyPlanningSceneService
[move_group-1] * - ClearOctomapService
[move_group-1] * - CartesianPathService
[move_group-1] * - ExecuteTrajectoryAction
[move_group-1] * - GetPlanningSceneService
[move_group-1] * - KinematicsService
[move_group-1] * - MoveAction
[move_group-1] * - MotionPlanService
[move_group-1] * - QueryPlannersService
[move_group-1] * - StateValidationService
[move_group-1] ********************************************************
[move_group-1]
[move_group-1] [INFO] [1715871120.496437346] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context using planning plugin pilz_industrial_motion_planner/CommandPlanner
[move_group-1] [INFO] [1715871120.496443752] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context initialization complete
[move_group-1] Loading 'move_group/ApplyPlanningSceneService'...
[move_group-1] Loading 'move_group/ClearOctomapService'...
[move_group-1] Loading 'move_group/MoveGroupCartesianPathService'...
[move_group-1] Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
[move_group-1] Loading 'move_group/MoveGroupGetPlanningSceneService'...
[move_group-1] Loading 'move_group/MoveGroupKinematicsService'...
[move_group-1] Loading 'move_group/MoveGroupMoveAction'...
[move_group-1] Loading 'move_group/MoveGroupPlanService'...
[move_group-1] Loading 'move_group/MoveGroupQueryPlannersService'...
[move_group-1] Loading 'move_group/MoveGroupStateValidationService'...
[move_group-1]
[move_group-1] You can start planning now!
[move_group-1]
[rviz2-2] [INFO] [1715871120.913908794] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1715871120.913966997] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[rviz2-2] [INFO] [1715871120.926865532] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] Warning: class_loader.impl: SEVERE WARNING!!! A namespace collision has occurred with plugin factory for class rviz_default_plugins::displays::InteractiveMarkerDisplay. New factory will OVERWRITE existing one. This situation occurs when libraries containing plugins are directly linked against an executable (the one running right now generating this message). Please separate plugins out into their own library or just don't link against the library and use either class_loader::ClassLoader/MultiLibraryClassLoader to open.
[rviz2-2] at line 253 in /opt/ros/humble/include/class_loader/class_loader/class_loader_core.hpp
[spawner-5] [INFO] [1715871121.992655608] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist
[spawner-6] [INFO] [1715871122.061492281] [spawner_joint_trajectory_controller]: Waiting for '/controller_manager' node to exist
[spawn_entity.py-9] [INFO] [1715871122.084614481] [spawn_ur]: Calling service /spawn_entity
[spawn_entity.py-9] [INFO] [1715871122.308717468] [spawn_ur]: Spawn status: SpawnEntity: Successfully spawned entity [ur]
[INFO] [spawn_entity.py-9]: process has finished cleanly [pid 123782]
[spawner-5] [INFO] [1715871124.000190217] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist
[rviz2-2] [ERROR] [1715871124.007834450] [moveit_ros_visualization.motion_planning_frame]: Action server: /recognize_objects not available
[rviz2-2] [INFO] [1715871124.016868794] [moveit_ros_visualization.motion_planning_frame]: MoveGroup namespace changed: / -> . Reloading params.
[spawner-6] [INFO] [1715871124.068937104] [spawner_joint_trajectory_controller]: Waiting for '/controller_manager' node to exist
[rviz2-2] Error: Joint 'basler_camera' declared as part of group 'camera' is not known to the URDF
[rviz2-2] at line 168 in ./src/model.cpp
[rviz2-2] Warning: Group 'camera' is empty.
[rviz2-2] at line 245 in ./src/model.cpp
[rviz2-2] [INFO] [1715871124.072605292] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00252864 seconds
[rviz2-2] [INFO] [1715871124.072647974] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[rviz2-2] [INFO] [1715871124.072658141] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[rviz2-2] [INFO] [1715871124.311860162] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[spawner-5] [INFO] [1715871126.007322427] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist
[spawner-6] [INFO] [1715871126.076062084] [spawner_joint_trajectory_controller]: Waiting for '/controller_manager' node to exist

[rviz2-2]
[spawner-5] [INFO] [1715871128.014371017] [spawner_joint_state_broadcaster]: Waiting for '/controller_manager' node to exist
[rviz2-2] [INFO] [1715871128.032025039] [interactive_marker_display_105792153429424]: Sending request for interactive markers
[rviz2-2] [INFO] [1715871128.074757025] [interactive_marker_display_105792153429424]: Service response received for initialization
[spawner-6] [INFO] [1715871128.082827837] [spawner_joint_trajectory_controller]: Waiting for '/controller_manager' node to exist
[spawner-5] [ERROR] [1715871130.021422289] [spawner_joint_state_broadcaster]: Controller manager not available
[spawner-6] [ERROR] [1715871130.089398457] [spawner_joint_trajectory_controller]: Controller manager not available
[ERROR] [spawner-5]: process has died [pid 123772, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args'].
[ERROR] [spawner-6]: process has died [pid 123774, exit code 1, cmd '/opt/ros/humble/lib/controller_manager/spawner joint_trajectory_controller -c /controller_manager --ros-args'].

Moveit execution fails: scaled_joint_trajectory_controller issue?

I'm having trouble using the motion planner on rviz. When I set a start and goal state and click plan, it works fine. Then when I hit execute it immediately fails. Here's the main issue:

[move_group-1] [INFO] [1707670870.360229842] [moveit_ros.trajectory_execution_manager]: Starting trajectory execution ... [move_group-1] [INFO] [1707670870.360380462] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1707670870.360478343] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [ERROR] [1707670870.360708389] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Action client not connected to action server: scaled_joint_trajectory_controller/follow_joint_trajectory [move_group-1] [ERROR] [1707670870.360728448] [moveit_ros.trajectory_execution_manager]: Failed to send trajectory part 1 of 1 to controller scaled_joint_trajectory_controller [move_group-1] [INFO] [1707670870.360816294] [moveit_ros.trajectory_execution_manager]: Completed trajectory execution with status ABORTED ... [move_group-1] [INFO] [1707670870.360968295] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution completed: ABORTED [rviz2-2] [INFO] [1707670870.361968868] [move_group_interface]: Execute request aborted

I've tried setting the use_mock_hardware flag to true but its the same issue. Any help would be so appreciated!

Here's the full terminal output:
ros2 launch ur_simulation_gazebo ur_sim_moveit.launch.py use_mock_hardware:=True [INFO] [launch]: All log files can be found below /home/tahira/.ros/log/2024-02-11-12-00-58-631161-tahira-Cyborg-15-A13VE-11236 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [move_group-1]: process started with pid [11244] [INFO] [rviz2-2]: process started with pid [11246] [INFO] [servo_node_main-3]: process started with pid [11248] [INFO] [robot_state_publisher-4]: process started with pid [11250] [INFO] [spawner-5]: process started with pid [11252] [INFO] [spawner-6]: process started with pid [11254] [INFO] [gzserver-7]: process started with pid [11256] [INFO] [gzclient-8]: process started with pid [11258] [INFO] [spawn_entity.py-9]: process started with pid [11260] [rviz2-2] Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway. [robot_state_publisher-4] [INFO] [1707670860.063610647] [robot_state_publisher]: got segment base [robot_state_publisher-4] [INFO] [1707670860.063685897] [robot_state_publisher]: got segment base_link [robot_state_publisher-4] [INFO] [1707670860.063691556] [robot_state_publisher]: got segment base_link_inertia [robot_state_publisher-4] [INFO] [1707670860.063694725] [robot_state_publisher]: got segment flange [robot_state_publisher-4] [INFO] [1707670860.063697231] [robot_state_publisher]: got segment forearm_link [robot_state_publisher-4] [INFO] [1707670860.063699707] [robot_state_publisher]: got segment ft_frame [robot_state_publisher-4] [INFO] [1707670860.063702291] [robot_state_publisher]: got segment shoulder_link [robot_state_publisher-4] [INFO] [1707670860.063704900] [robot_state_publisher]: got segment tool0 [robot_state_publisher-4] [INFO] [1707670860.063707285] [robot_state_publisher]: got segment upper_arm_link [robot_state_publisher-4] [INFO] [1707670860.063709800] [robot_state_publisher]: got segment world [robot_state_publisher-4] [INFO] [1707670860.063712143] [robot_state_publisher]: got segment wrist_1_link [robot_state_publisher-4] [INFO] [1707670860.063714492] [robot_state_publisher]: got segment wrist_2_link [robot_state_publisher-4] [INFO] [1707670860.063716758] [robot_state_publisher]: got segment wrist_3_link [move_group-1] [WARN] [1707670860.077489780] [move_group.move_group]: Falling back to using the the move_group node namespace (deprecated behavior). [servo_node_main-3] [WARN] [1707670860.079530042] [moveit_servo.servo_node]: Intra-process communication is disabled, consider enabling it by adding: [servo_node_main-3] extra_arguments=[{'use_intra_process_comms' : True}] [servo_node_main-3] to the Servo composable node in the launch file [move_group-1] [INFO] [1707670860.080883730] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0 seconds [move_group-1] [INFO] [1707670860.080918300] [moveit_robot_model.robot_model]: Loading robot model 'ur'... [move_group-1] [INFO] [1707670860.080932936] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint [servo_node_main-3] [INFO] [1707670860.083009749] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00194123 seconds [servo_node_main-3] [INFO] [1707670860.083027402] [moveit_robot_model.robot_model]: Loading robot model 'ur'... [servo_node_main-3] [INFO] [1707670860.083033106] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint [servo_node_main-3] [WARN] [1707670860.091699359] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml! [servo_node_main-3] [INFO] [1707670860.117594098] [moveit_ros.current_state_monitor]: Listening to joint states on topic '/joint_states' [servo_node_main-3] [INFO] [1707670860.120496599] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects [servo_node_main-3] [INFO] [1707670860.120512858] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor [servo_node_main-3] [INFO] [1707670860.121162992] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene' [servo_node_main-3] [INFO] [1707670860.121361676] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on '/servo_node/publish_planning_scene' [servo_node_main-3] [WARN] [1707670860.126706604] [moveit_servo.servo_calcs]: No kinematics solver instantiated for group 'ur_manipulator'. Will use inverse Jacobian for servo calculations instead. [servo_node_main-3] [WARN] [1707670860.126726367] [moveit_servo.collision_check]: Collision check rate is low, increase it in yaml file if CPU allows [move_group-1] [INFO] [1707670860.138690027] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene' [move_group-1] [INFO] [1707670860.138791303] [moveit.ros_planning_interface.moveit_cpp]: Listening to 'joint_states' for joint states [move_group-1] [INFO] [1707670860.139182488] [moveit_ros.current_state_monitor]: Listening to joint states on topic 'joint_states' [move_group-1] [INFO] [1707670860.139341118] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects [move_group-1] [INFO] [1707670860.139351202] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor [move_group-1] [INFO] [1707670860.139456282] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene' [move_group-1] [INFO] [1707670860.139462841] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting world geometry update monitor for collision objects, attached objects, octomap updates. [move_group-1] [INFO] [1707670860.139788511] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'collision_object' [move_group-1] [INFO] [1707670860.139982289] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry [move_group-1] [WARN] [1707670860.140906224] [moveit.ros.occupancy_map_monitor.middleware_handle]: Resolution not specified for Octomap. Assuming resolution = 0.1 instead [move_group-1] [ERROR] [1707670860.140921211] [moveit.ros.occupancy_map_monitor.middleware_handle]: No 3D sensor plugin(s) defined for octomap updates [move_group-1] [INFO] [1707670860.144324883] [moveit.ros_planning_interface.moveit_cpp]: Loading planning pipeline 'move_group' [move_group-1] [INFO] [1707670860.158718034] [moveit.ros_planning.planning_pipeline]: Using planning interface 'OMPL' [move_group-1] [INFO] [1707670860.163318680] [moveit_ros.add_time_optimal_parameterization]: Param 'move_group.path_tolerance' was not set. Using default value: 0.100000 [move_group-1] [INFO] [1707670860.163335383] [moveit_ros.add_time_optimal_parameterization]: Param 'move_group.resample_dt' was not set. Using default value: 0.100000 [move_group-1] [INFO] [1707670860.163340074] [moveit_ros.add_time_optimal_parameterization]: Param 'move_group.min_angle_change' was not set. Using default value: 0.001000 [move_group-1] [INFO] [1707670860.163355651] [moveit_ros.fix_workspace_bounds]: Param 'move_group.default_workspace_bounds' was not set. Using default value: 10.000000 [move_group-1] [INFO] [1707670860.163370377] [moveit_ros.fix_start_state_bounds]: Param 'move_group.start_state_max_bounds_error' was set to 0.100000 [move_group-1] [INFO] [1707670860.163374497] [moveit_ros.fix_start_state_bounds]: Param 'move_group.start_state_max_dt' was not set. Using default value: 0.500000 [move_group-1] [INFO] [1707670860.163385752] [moveit_ros.fix_start_state_collision]: Param 'move_group.start_state_max_dt' was not set. Using default value: 0.500000 [move_group-1] [INFO] [1707670860.163390035] [moveit_ros.fix_start_state_collision]: Param 'move_group.jiggle_fraction' was not set. Using default value: 0.020000 [move_group-1] [INFO] [1707670860.163399188] [moveit_ros.fix_start_state_collision]: Param 'move_group.max_sampling_attempts' was not set. Using default value: 100 [move_group-1] [INFO] [1707670860.163409581] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Add Time Optimal Parameterization' [move_group-1] [INFO] [1707670860.163415251] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Workspace Bounds' [move_group-1] [INFO] [1707670860.163418913] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Bounds' [move_group-1] [INFO] [1707670860.163421912] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State In Collision' [move_group-1] [INFO] [1707670860.163425024] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Path Constraints' [move_group-1] [INFO] [1707670860.185460595] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for scaled_joint_trajectory_controller [move_group-1] [INFO] [1707670860.187559084] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for joint_trajectory_controller [move_group-1] [INFO] [1707670860.187662952] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1707670860.187689803] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1707670860.188170084] [moveit_ros.trajectory_execution_manager]: Trajectory execution is not managing controllers [move_group-1] [INFO] [1707670860.188182873] [move_group.move_group]: MoveGroup debug mode is ON [move_group-1] [INFO] [1707670860.213350293] [move_group.move_group]: [move_group-1] [move_group-1] ******************************************************** [move_group-1] * MoveGroup using: [move_group-1] * - ApplyPlanningSceneService [move_group-1] * - ClearOctomapService [move_group-1] * - CartesianPathService [move_group-1] * - ExecuteTrajectoryAction [move_group-1] * - GetPlanningSceneService [move_group-1] * - KinematicsService [move_group-1] * - MoveAction [move_group-1] * - MotionPlanService [move_group-1] * - QueryPlannersService [move_group-1] * - StateValidationService [move_group-1] ******************************************************** [move_group-1] [move_group-1] [INFO] [1707670860.213385710] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner [move_group-1] [INFO] [1707670860.213392151] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context initialization complete [move_group-1] Loading 'move_group/ApplyPlanningSceneService'... [move_group-1] Loading 'move_group/ClearOctomapService'... [move_group-1] Loading 'move_group/MoveGroupCartesianPathService'... [move_group-1] Loading 'move_group/MoveGroupExecuteTrajectoryAction'... [move_group-1] Loading 'move_group/MoveGroupGetPlanningSceneService'... [move_group-1] Loading 'move_group/MoveGroupKinematicsService'... [move_group-1] Loading 'move_group/MoveGroupMoveAction'... [move_group-1] Loading 'move_group/MoveGroupPlanService'... [move_group-1] Loading 'move_group/MoveGroupQueryPlannersService'... [move_group-1] Loading 'move_group/MoveGroupStateValidationService'... [move_group-1] [move_group-1] You can start planning now! [move_group-1] [rviz2-2] [INFO] [1707670860.372821546] [rviz2]: Stereo is NOT SUPPORTED [rviz2-2] [INFO] [1707670860.372870195] [rviz2]: OpenGl version: 4.6 (GLSL 4.6) [rviz2-2] [INFO] [1707670860.383272685] [rviz2]: Stereo is NOT SUPPORTED [spawn_entity.py-9] [INFO] [1707670860.429796254] [spawn_ur]: Spawn Entity started [spawn_entity.py-9] [INFO] [1707670860.429998581] [spawn_ur]: Loading entity published on topic robot_description [spawn_entity.py-9] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead. [spawn_entity.py-9] warnings.warn( [spawn_entity.py-9] [INFO] [1707670860.431462008] [spawn_ur]: Waiting for entity xml on robot_description [spawn_entity.py-9] [INFO] [1707670860.442796635] [spawn_ur]: Waiting for service /spawn_entity, timeout = 30 [spawn_entity.py-9] [INFO] [1707670860.443045810] [spawn_ur]: Waiting for service /spawn_entity [rviz2-2] Warning: class_loader.impl: SEVERE WARNING!!! A namespace collision has occurred with plugin factory for class rviz_default_plugins::displays::InteractiveMarkerDisplay. New factory will OVERWRITE existing one. This situation occurs when libraries containing plugins are directly linked against an executable (the one running right now generating this message). Please separate plugins out into their own library or just don't link against the library and use either class_loader::ClassLoader/MultiLibraryClassLoader to open. [rviz2-2] at line 253 in /opt/ros/humble/include/class_loader/class_loader/class_loader_core.hpp [spawn_entity.py-9] [INFO] [1707670860.948847900] [spawn_ur]: Calling service /spawn_entity [spawn_entity.py-9] [INFO] [1707670861.256663836] [spawn_ur]: Spawn status: SpawnEntity: Successfully spawned entity [ur] [gzserver-7] [INFO] [1707670861.278149294] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin [gzserver-7] [INFO] [1707670861.280393439] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: / [gzserver-7] [INFO] [1707670861.280583309] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control [gzserver-7] [INFO] [1707670861.280636675] [gazebo_ros2_control]: Loading parameter files /home/tahira/workspaces/ur_gazebo/install/ur_simulation_gazebo/share/ur_simulation_gazebo/config/ur_controllers.yaml [gzserver-7] [INFO] [1707670861.284318135] [gazebo_ros2_control]: connected to service!! robot_state_publisher [gzserver-7] [INFO] [1707670861.284731299] [gazebo_ros2_control]: Received urdf from param server, parsing... [gzserver-7] text not specified in the tf_prefix tag [gzserver-7] text not specified in the tf_prefix tag [gzserver-7] [ERROR] [1707670861.290940989] [gazebo_ros2_control]: The plugin failed to load for some reason. Error: According to the loaded plugin descriptions the class ur_robot_driver/URPositionHardwareInterface with base class type gazebo_ros2_control::GazeboSystemInterface does not exist. Declared types are gazebo_ros2_control/GazeboSystem [gzserver-7] [gzserver-7] [INFO] [1707670861.298643558] [gazebo_ros2_control]: Loading joint: shoulder_pan_joint [gzserver-7] [INFO] [1707670861.298675362] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298682943] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298699926] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298709104] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298713270] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298717797] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.298726860] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298731382] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.298735027] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298769086] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298774866] [gazebo_ros2_control]: Loading joint: shoulder_lift_joint [gzserver-7] [INFO] [1707670861.298778817] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298782537] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298786730] [gazebo_ros2_control]: found initial value: -1.570000 [gzserver-7] [INFO] [1707670861.298791352] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298794743] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298798817] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.298802237] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298806091] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.298809498] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298819171] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298823672] [gazebo_ros2_control]: Loading joint: elbow_joint [gzserver-7] [INFO] [1707670861.298827574] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298831162] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298834527] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298838482] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298841753] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298845576] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.298849722] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298853667] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.298857036] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298864778] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298869105] [gazebo_ros2_control]: Loading joint: wrist_1_joint [gzserver-7] [INFO] [1707670861.298872738] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298876153] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298879825] [gazebo_ros2_control]: found initial value: -1.570000 [gzserver-7] [INFO] [1707670861.298883852] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298887061] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298890954] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.298894282] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298898104] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.298901586] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298929505] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298933865] [gazebo_ros2_control]: Loading joint: wrist_2_joint [gzserver-7] [INFO] [1707670861.298937453] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298940919] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298944180] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298948039] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298951206] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298955011] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.298958275] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298961998] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.298965328] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298972258] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298976607] [gazebo_ros2_control]: Loading joint: wrist_3_joint [gzserver-7] [INFO] [1707670861.298980333] [gazebo_ros2_control]: State: [gzserver-7] [INFO] [1707670861.298983769] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.298987092] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298990942] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.298995136] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.298999264] [gazebo_ros2_control]: effort [gzserver-7] [INFO] [1707670861.299002523] [gazebo_ros2_control]: found initial value: 0.000000 [gzserver-7] [INFO] [1707670861.299006407] [gazebo_ros2_control]: Command: [gzserver-7] [INFO] [1707670861.299009978] [gazebo_ros2_control]: position [gzserver-7] [INFO] [1707670861.299015173] [gazebo_ros2_control]: velocity [gzserver-7] [INFO] [1707670861.299051801] [resource_manager]: Initialize hardware 'ur' [gzserver-7] [INFO] [1707670861.299151271] [resource_manager]: Successful initialization of hardware 'ur' [gzserver-7] [INFO] [1707670861.299264129] [resource_manager]: 'configure' hardware 'ur' [gzserver-7] [INFO] [1707670861.299270760] [resource_manager]: Successful 'configure' of hardware 'ur' [gzserver-7] [INFO] [1707670861.299281923] [resource_manager]: 'activate' hardware 'ur' [gzserver-7] [INFO] [1707670861.299285731] [resource_manager]: Successful 'activate' of hardware 'ur' [gzserver-7] [INFO] [1707670861.299328016] [gazebo_ros2_control]: Loading controller_manager [gzserver-7] [WARN] [1707670861.314329866] [gazebo_ros2_control]: Desired controller update period (0.01 s) is slower than the gazebo simulation period (0.001 s). [gzserver-7] [INFO] [1707670861.314473939] [gazebo_ros2_control]: Loaded gazebo_ros2_control. [gzserver-7] [INFO] [1707670861.340560248] [controller_manager]: Loading controller 'joint_state_broadcaster' [spawner-5] [INFO] [1707670861.365956201] [spawner_joint_state_broadcaster]: Loaded joint_state_broadcaster [gzserver-7] [INFO] [1707670861.367297781] [controller_manager]: Loading controller 'joint_trajectory_controller' [INFO] [spawn_entity.py-9]: process has finished cleanly [pid 11260] [gzserver-7] [WARN] [1707670861.385198308] [joint_trajectory_controller]: [Deprecated]: "allow_nonzero_velocity_at_trajectory_end" is set to true. The default behavior will change to false. [gzserver-7] [INFO] [1707670861.394770574] [controller_manager]: Configuring controller 'joint_state_broadcaster' [gzserver-7] [INFO] [1707670861.394961513] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published [spawner-6] [INFO] [1707670861.395290362] [spawner_joint_trajectory_controller]: Loaded joint_trajectory_controller [gzserver-7] [INFO] [1707670861.404797575] [controller_manager]: Configuring controller 'joint_trajectory_controller' [gzserver-7] [INFO] [1707670861.404931988] [joint_trajectory_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter. [gzserver-7] [INFO] [1707670861.404975657] [joint_trajectory_controller]: Command interfaces are [position] and state interfaces are [position velocity]. [gzserver-7] [INFO] [1707670861.404988406] [joint_trajectory_controller]: Using 'splines' interpolation method. [gzserver-7] [INFO] [1707670861.406070464] [joint_trajectory_controller]: Controller state will be published at 100.00 Hz. [gzserver-7] [INFO] [1707670861.407151441] [joint_trajectory_controller]: Action status changes will be monitored at 20.00 Hz. [spawner-5] [INFO] [1707670861.435092485] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster [spawner-6] [INFO] [1707670861.455178451] [spawner_joint_trajectory_controller]: Configured and activated joint_trajectory_controller [INFO] [spawner-5]: process has finished cleanly [pid 11252] [INFO] [spawner-6]: process has finished cleanly [pid 11254] [rviz2-2] [ERROR] [1707670863.492295517] [moveit_ros_visualization.motion_planning_frame]: Action server: /recognize_objects not available [rviz2-2] [INFO] [1707670863.529022221] [moveit_ros_visualization.motion_planning_frame]: MoveGroup namespace changed: / -> . Reloading params. [rviz2-2] [INFO] [1707670863.597802410] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00302019 seconds [rviz2-2] [INFO] [1707670863.597834689] [moveit_robot_model.robot_model]: Loading robot model 'ur'... [rviz2-2] [INFO] [1707670863.597845141] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint [rviz2-2] [INFO] [1707670863.647274731] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor [rviz2-2] [INFO] [1707670863.647782546] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/monitored_planning_scene' [rviz2-2] [INFO] [1707670863.805669357] [interactive_marker_display_94526503659280]: Connected on namespace: /rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic [rviz2-2] [INFO] [1707670863.808907711] [moveit_ros_visualization.motion_planning_frame]: group ur_manipulator [rviz2-2] [INFO] [1707670863.808921232] [moveit_ros_visualization.motion_planning_frame]: Constructing new MoveGroup connection for group 'ur_manipulator' in namespace '' [rviz2-2] [INFO] [1707670863.812905169] [move_group_interface]: Ready to take commands for planning group ur_manipulator. [rviz2-2] [INFO] [1707670863.814270539] [interactive_marker_display_94526503659280]: Sending request for interactive markers [rviz2-2] [INFO] [1707670863.847449886] [interactive_marker_display_94526503659280]: Service response received for initialization [rviz2-2] [INFO] [1707670867.927490361] [move_group_interface]: MoveGroup action client/server ready [move_group-1] [INFO] [1707670867.928418149] [moveit_move_group_default_capabilities.move_action_capability]: Received request [move_group-1] [INFO] [1707670867.928713480] [moveit_move_group_default_capabilities.move_action_capability]: executing.. [move_group-1] [INFO] [1707670867.928927845] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [rviz2-2] [INFO] [1707670867.928784622] [move_group_interface]: Planning request accepted [move_group-1] [INFO] [1707670867.928973397] [moveit_move_group_capabilities_base.move_group_capability]: Using planning pipeline 'move_group' [move_group-1] [INFO] [1707670867.930384407] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-1] [WARN] [1707670868.006266478] [moveit_trajectory_processing.time_optimal_trajectory_generation]: Joint acceleration limits are not defined. Using the default 1 rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml. [move_group-1] [INFO] [1707670868.006559977] [moveit_move_group_default_capabilities.move_action_capability]: Motion plan was computed successfully. [rviz2-2] [INFO] [1707670868.006884715] [move_group_interface]: Planning request complete! [rviz2-2] [INFO] [1707670868.007273746] [move_group_interface]: time taken to generate plan: 0.0218485 seconds [move_group-1] [INFO] [1707670870.352522330] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Received goal request [move_group-1] [INFO] [1707670870.352852717] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution request received [move_group-1] [INFO] [1707670870.352933644] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1707670870.352988521] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [rviz2-2] [INFO] [1707670870.353095992] [move_group_interface]: Execute request accepted [move_group-1] [INFO] [1707670870.353257785] [moveit_ros.trajectory_execution_manager]: Validating trajectory with allowed_start_tolerance 0.01 [move_group-1] [INFO] [1707670870.360229842] [moveit_ros.trajectory_execution_manager]: Starting trajectory execution ... [move_group-1] [INFO] [1707670870.360380462] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1707670870.360478343] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [ERROR] [1707670870.360708389] [moveit.simple_controller_manager.follow_joint_trajectory_controller_handle]: Action client not connected to action server: scaled_joint_trajectory_controller/follow_joint_trajectory [move_group-1] [ERROR] [1707670870.360728448] [moveit_ros.trajectory_execution_manager]: Failed to send trajectory part 1 of 1 to controller scaled_joint_trajectory_controller [move_group-1] [INFO] [1707670870.360816294] [moveit_ros.trajectory_execution_manager]: Completed trajectory execution with status ABORTED ... [move_group-1] [INFO] [1707670870.360968295] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution completed: ABORTED [rviz2-2] [INFO] [1707670870.361968868] [move_group_interface]: Execute request aborted [rviz2-2] [ERROR] [1707670870.362815530] [move_group_interface]: MoveGroupInterface::execute() failed or timeout reached [rviz2-2] [WARN] [1707670870.961803940] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Maybe failed to update robot state, time diff: 1707670860.587s

Robot Movement Velocity

Hi everyone,

i'm trying to set the movement speed of the ur in my simulation. Unfortunately i don't know how to do that since i'm only sending a joint trajectory to the respective topic. Does anyone know how to set the velocity so that the robot can move faster/slower than the default?

Galactic: is there a way to have Gazebo simulation working

I’m struggling with running Gazebo simulation with MoveIT.
I have launched two commands:
ros2 launch ur_simulation_gazebo ur_sim_control.launch.py initial_joint_controller:=joint_trajectory_controller launch_rviz:=false
and
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true
hoping that this works around the #8

It seems working, a I can plan a movement but the execute command fails. In the log the worrying lines are about “Failed to validate trajectory: couldn't receive full current joint state within 1s”. So If I correctly understand the trajectory is sent but there is no info back from Gazebo simulation about the robot state. Is it a problem of Gazebo_ros_control or am I missing sth in the config?

Could anybody help?

The longer log is as follows:
[rviz2-3] [INFO] [1646127072.138752918] [move_group_interface]: MoveGroup action client/server ready [move_group-1] [INFO] [1646127072.140623611] [moveit_move_group_default_capabilities.move_action_capability]: Received request [move_group-1] [INFO] [1646127072.140978066] [moveit_move_group_default_capabilities.move_action_capability]: executing.. [rviz2-3] [INFO] [1646127072.342920831] [move_group_interface]: Planning request accepted [move_group-1] [INFO] [1646127073.141161483] [moveit_ros.current_state_monitor]: Didn't received robot state (joint angles) with recent timestamp within 1.000000 seconds. [move_group-1] Check clock synchronization if your are running ROS across multiple machines! [move_group-1] [WARN] [1646127073.141208034] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Failed to fetch current robot state. [move_group-1] [INFO] [1646127073.141287931] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline. [move_group-1] [INFO] [1646127073.141318225] [moveit_move_group_capabilities_base.move_group_capability]: Using planning pipeline 'move_group' [move_group-1] [INFO] [1646127073.148626788] [moveit.ompl_planning.model_based_planning_context]: Planner configuration 'ur_manipulator' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [move_group-1] [INFO] [1646127073.184540385] [moveit_move_group_default_capabilities.move_action_capability]: Motion plan was computed successfully. [rviz2-3] [INFO] [1646127073.446626486] [move_group_interface]: Planning request complete! [rviz2-3] [INFO] [1646127073.547046436] [move_group_interface]: time taken to generate plan: 0.0273636 seconds [move_group-1] [INFO] [1646127077.708584645] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Received goal request [move_group-1] [INFO] [1646127077.708854131] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution request received [move_group-1] [INFO] [1646127077.708912702] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list [move_group-1] [INFO] [1646127077.709189930] [moveit_ros.trajectory_execution_manager]: Validating trajectory with allowed_start_tolerance 0.01 [rviz2-3] [INFO] [1646127077.910754393] [move_group_interface]: Execute request accepted [move_group-1] [INFO] [1646127078.709362662] [moveit_ros.current_state_monitor]: Didn't received robot state (joint angles) with recent timestamp within 1.000000 seconds. [move_group-1] Check clock synchronization if your are running ROS across multiple machines! [move_group-1] [WARN] [1646127078.709401107] [moveit_ros.trajectory_execution_manager]: Failed to validate trajectory: couldn't receive full current joint state within 1s [move_group-1] [INFO] [1646127078.709452013] [moveit_move_group_default_capabilities.execute_trajectory_action_capability]: Execution completed: ABORTED [rviz2-3] [INFO] [1646127079.014918702] [move_group_interface]: Execute request aborted [rviz2-3] [ERROR] [1646127079.115353458] [move_group_interface]: MoveGroupInterface::execute() failed or timeout reached [rviz2-3] [WARN] [1646127079.852387667] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Maybe failed to update robot state, time diff: 1646127003.702s

can not build on ros2 humble

Summary: 74 packages finished [31.6s]
6 packages had stderr output: controller_manager moveit_configs_utils ros2_controllers_test_nodes ros2controlcli rqt_controller_manager rqt_joint_trajectory_controller

ex:
stderr: ros2controlcli
/usr/lib/python3/dist-packages/setuptools/command/easy_install.py:158: EasyInstallDeprecationWarning: easy_install command is deprecated. Use build and pip and other standards-based tools.

UR5 not working correctly

The UR5 seems not to be simulated correctly. It's the only robot that shakes directly after start. While with the others I can execute trajectories, with the UR5 this doesn't work.

UR control via Ros2 Humble Python node

Hi everyone,

this isn't really an issue, but since there is no Disscussion-Section here I thought that I would ask my question here.

I'm trying to control the joints of an ur10 (in Gazebo) via a node. I construct a FollowJointTrajectory.Goal() message and I'm trying to send that via an ActionClient(self, FollowJointTrajectory, "joint_trajectory_controller).

Unfortunately I get stuck when I'm waiting for the server, which I thought was being spawned when launching the UR. Does anyone know what's going on and wants to help me?

So here' my code:

#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.action import ActionClient
from rclpy.time import Duration

from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from control_msgs.action import FollowJointTrajectory


class Ur10ManualJoints(Node):
    
    def __init__(self):
        super().__init__('Ur10ManualJoints')
        self.actionClient = ActionClient(self, FollowJointTrajectory, '/joint_trajectory_controller')

        self.execute()


    def sendTrajGoal(self, joint_namen, joint_pos, duration):
        zielMsg = FollowJointTrajectory.Goal()
        zielMsg.trajectory.joint_names = joint_namen

        pkt = JointTrajectoryPoint()
        pkt.positions = joint_pos
        pkt.time_from_start = duration

        zielMsg.trajectory.points.append(pkt)

        self.get_logger().info("waiting for server...")
        self.actionClient.wait_for_server()
        self.get_logger().info("sending Action Goal...")
        self.actionClient.send_goal_async(zielMsg) #vllt mit return
        self.get_logger().info("Action Goal sent!")

    def execute(self):
        jointNamen = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']

        jointPos = []

        for jointName in jointNamen:
            pos = input(f"Enter position for {jointName}:")
            jointPos.append(float(pos))

        duration = rclpy.time.Duration(seconds=5).to_msg()

        self.sendTrajGoal(jointNamen, jointPos, duration)



def main(args=None):
    rclpy.init(args=args)
    node = Ur10ManualJoints()
    rclpy.spin(node)
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Doesn't work on Galactic

Hi,

I just compiled the package successfully and ran this command:

ros2 launch ur_simulation_gazebo ur_sim_control.launch.py

Ended up with a lot of errors starting with an import error.

[spawn_entity.py-6]   warnings.warn(
[spawn_entity.py-6] Traceback (most recent call last):
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/rosidl_generator_py/import_type_support_impl.py", line 46, in import_type_support
[spawn_entity.py-6]     return importlib.import_module(module_name, package=pkg_name)
[spawn_entity.py-6]   File "/usr/lib/python3.8/importlib/__init__.py", line 127, in import_module
[spawn_entity.py-6]     return _bootstrap._gcd_import(name[level:], package, level)
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 1014, in _gcd_import
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 991, in _find_and_load
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 975, in _find_and_load_unlocked
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 657, in _load_unlocked
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 556, in module_from_spec
[spawn_entity.py-6]   File "<frozen importlib._bootstrap_external>", line 1166, in create_module
[spawn_entity.py-6]   File "<frozen importlib._bootstrap>", line 219, in _call_with_frames_removed
[spawn_entity.py-6] ImportError: /opt/ros/galactic/lib/libgazebo_msgs__rosidl_generator_c.so: undefined symbol: geometry_msgs__msg__Vector3__Sequence__are_equal
[spawn_entity.py-6] 
[spawn_entity.py-6] During handling of the above exception, another exception occurred:
[spawn_entity.py-6] 
[spawn_entity.py-6] Traceback (most recent call last):
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py", line 365, in <module>
[spawn_entity.py-6]     main()
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py", line 360, in main
[spawn_entity.py-6]     exit_code = spawn_entity_node.run()
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py", line 223, in run
[spawn_entity.py-6]     success = self._spawn_entity(entity_xml, initial_pose, self.args.spawn_service_timeout)
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py", line 270, in _spawn_entity
[spawn_entity.py-6]     client = self.create_client(SpawnEntity, '%s/spawn_entity' % self.args.gazebo_namespace)
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/rclpy/node.py", line 1407, in create_client
[spawn_entity.py-6]     check_is_valid_srv_type(srv_type)
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/rclpy/type_support.py", line 51, in check_is_valid_srv_type
[spawn_entity.py-6]     check_for_type_support(srv_type)
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/rclpy/type_support.py", line 29, in check_for_type_support
[spawn_entity.py-6]     msg_or_srv_type.__class__.__import_type_support__()
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/gazebo_msgs/srv/_spawn_entity.py", line 355, in __import_type_support__
[spawn_entity.py-6]     module = import_type_support('gazebo_msgs')
[spawn_entity.py-6]   File "/opt/ros/galactic/lib/python3.8/site-packages/rosidl_generator_py/import_type_support_impl.py", line 48, in import_type_support
[spawn_entity.py-6]     raise UnsupportedTypeSupport(pkg_name)
[spawn_entity.py-6] rosidl_generator_py.import_type_support_impl.UnsupportedTypeSupport: Could not import 'rosidl_typesupport_c' for package 'gazebo_msgs'
[ERROR] [spawn_entity.py-6]: process has died [pid 3073, exit code 1, cmd '/opt/ros/galactic/lib/gazebo_ros/spawn_entity.py -entity ur -topic robot_description --ros-args -r __node:=spawn_ur'].

Kindly help. Thanks.

Update README and CI

The currend README and CI is rather outdated. We should make things up-to-date with ROS Humle, Iron and Rolling.

Add integration tests for Gazebo simulation

Integration tests would help us ensure that things stay functional. Tests should

  • Spawn robot and execute a trajectory
  • Spawn robot and MoveIt, plan end execute trajectory.

Keeps requiring ur_joint_control even though it doesnt come with it (ROS2 Humble)

[INFO] [launch]: All log files can be found below /home/lusmse/.ros/log/2024-03-20-22-02-53-812384-lusmse-5237
[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): executed command failed. Command: /opt/ros/humble/bin/xacro /home/lusmse/workspaces/ur_gazebo/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.urdf.xacro safety_limits:=true safety_pos_margin:=0.15 safety_k_position:=20 name:=ur ur_type:=ur5e prefix:="" simulation_controllers:=/home/lusmse/workspaces/ur_gazebo/install/ur_simulation_gazebo/share/ur_simulation_gazebo/config/ur_controllers.yaml
Captured stderr output: error: No such file or directory: /opt/ros/humble/share/ur_description/urdf/inc/ur_joint_control.xacro [Errno 2] No such file or directory: '/opt/ros/humble/share/ur_description/urdf/inc/ur_joint_control.xacro'
when processing file: /home/lusmse/workspaces/ur_gazebo/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.ros2_control.xacro
included from: /home/lusmse/workspaces/ur_gazebo/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.urdf.xacro

[humble] can not control robot with MoveIt

The launch file ur_sim_moveit.launch brings up the simulation and moveit (from the UR_Description/ur_moveit_config package).

Simulation runs with the joint_trajectory_controller, whereas the real robot uses the scaled_trajectory_controller.

To work out of the box, one needs to add the "use_fake_hardware" argument to the launch file so it switches the default controller automatically (see https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_moveit_config/launch/ur_moveit.launch.py#L170).

As far as I know this only applies to humble, since galactic is running on joint_trajectory_controller anyways.

Will open a PR to add this.

Cannot start simulated controller

I've just tested the package again locally and I couldn't get it running. My robot collapses in Gazebo.

Tested on galactic and rolling

ros2 launch ur_simulation_gazebo ur_sim_control.launch.py launch_rviz:=false
[INFO] [launch]: All log files can be found below /home/mauch/.ros/log/2022-02-17-17-33-48-428280-ids-felino-1467787
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [1467792]
[INFO] [spawner-2]: process started with pid [1467794]
[INFO] [spawner-3]: process started with pid [1467796]
[INFO] [gzserver-4]: process started with pid [1467798]
[INFO] [gzclient   -5]: process started with pid [1467800]
[INFO] [spawn_entity.py-6]: process started with pid [1467803]
[robot_state_publisher-1] Link base_link had 2 children
[robot_state_publisher-1] Link base had 0 children
[robot_state_publisher-1] Link base_link_inertia had 1 children
[robot_state_publisher-1] Link shoulder_link had 1 children
[robot_state_publisher-1] Link upper_arm_link had 1 children
[robot_state_publisher-1] Link forearm_link had 1 children
[robot_state_publisher-1] Link wrist_1_link had 1 children
[robot_state_publisher-1] Link wrist_2_link had 1 children
[robot_state_publisher-1] Link wrist_3_link had 2 children
[robot_state_publisher-1] Link flange had 1 children
[robot_state_publisher-1] Link tool0 had 0 children
[robot_state_publisher-1] Link ft_frame had 0 children
[robot_state_publisher-1] [INFO] [1645115629.849598149] [robot_state_publisher]: got segment base
[robot_state_publisher-1] [INFO] [1645115629.849816430] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1645115629.849829497] [robot_state_publisher]: got segment base_link_inertia
[robot_state_publisher-1] [INFO] [1645115629.849835587] [robot_state_publisher]: got segment flange
[robot_state_publisher-1] [INFO] [1645115629.849840830] [robot_state_publisher]: got segment forearm_link
[robot_state_publisher-1] [INFO] [1645115629.849845750] [robot_state_publisher]: got segment ft_frame
[robot_state_publisher-1] [INFO] [1645115629.849850729] [robot_state_publisher]: got segment shoulder_link
[robot_state_publisher-1] [INFO] [1645115629.849855794] [robot_state_publisher]: got segment tool0
[robot_state_publisher-1] [INFO] [1645115629.849860601] [robot_state_publisher]: got segment upper_arm_link
[robot_state_publisher-1] [INFO] [1645115629.849865675] [robot_state_publisher]: got segment world
[robot_state_publisher-1] [INFO] [1645115629.849870454] [robot_state_publisher]: got segment wrist_1_link
[robot_state_publisher-1] [INFO] [1645115629.849875341] [robot_state_publisher]: got segment wrist_2_link
[robot_state_publisher-1] [INFO] [1645115629.849880039] [robot_state_publisher]: got segment wrist_3_link
[spawner-3] [INFO] [1645115630.018245809] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1645115630.023778367] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawn_entity.py-6] [INFO] [1645115630.221397392] [spawn_ur]: Spawn Entity started
[spawn_entity.py-6] [INFO] [1645115630.221701841] [spawn_ur]: Loading entity published on topic robot_description
[spawn_entity.py-6] [INFO] [1645115630.223669776] [spawn_ur]: Waiting for entity xml on robot_description
[spawn_entity.py-6] [INFO] [1645115630.226405134] [spawn_ur]: Waiting for service /spawn_entity, timeout = 5
[spawn_entity.py-6] [INFO] [1645115630.226649655] [spawn_ur]: Waiting for service /spawn_entity
[spawn_entity.py-6] [INFO] [1645115631.235188872] [spawn_ur]: Calling service /spawn_entity
[spawn_entity.py-6] [INFO] [1645115631.342849033] [spawn_ur]: Spawn status: SpawnEntity: Successfully spawned entity [ur]
[spawn_entity.py-6] /opt/ros/rolling/lib/python3.8/site-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.
[spawn_entity.py-6]   warnings.warn(
[INFO] [spawn_entity.py-6]: process has finished cleanly [pid 1467803]
[spawner-3] [INFO] [1645115632.024827197] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1645115632.030173033] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1645115634.031438651] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1645115634.036481980] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1645115636.037947883] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1645115636.043177276] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [INFO] [1645115638.044545151] [spawner_joint_trajectory_controller]: Waiting for /controller_manager services
[spawner-2] [INFO] [1645115638.049869327] [spawner_joint_state_broadcaster]: Waiting for /controller_manager services
[spawner-3] [ERROR] [1645115640.051332917] [spawner_joint_trajectory_controller]: Controller manager not available
[spawner-2] [ERROR] [1645115640.056365590] [spawner_joint_state_broadcaster]: Controller manager not available
[ERROR] [spawner-3]: process has died [pid 1467796, exit code 1, cmd '/opt/ros/rolling/lib/controller_manager/spawner joint_trajectory_controller -c /controller_manager --ros-args'].
[ERROR] [spawner-2]: process has died [pid 1467794, exit code 1, cmd '/opt/ros/rolling/lib/controller_manager/spawner joint_state_broadcaster --controller-manager /controller_manager --ros-args'].

I'll leave this as a comment for now.

Missing launch file for moveit

Hi everyone,

I installed the Gazebo simulator as per instructions, using Ubuntu 20.04 and ROS2 Galactic. Launching ros2 launch ur_simulation_gazebo ur_sim_control.launch.py works like a charm. I then try to launch the test_controller as described with ros2 launch ur_bringup test_joint_trajectory_controller.launch.py and I don't get anything moving. as I get the output from this node: https://pastebin.com/p028hS6Z

But, more importantly (for me) is that when I try to launch the configuration with gazebo and MoveIt with ros2 launch ur_simulation_gazebo ur_sim_moveit.launch.py I get: https://pastebin.com/LQqBprDy

And, fair enough, I get no launch folder there: https://pastebin.com/raw/LWGXwzrp

Build Error

Error is as follows:

--- stderr: controller_manager                                           
/home/jayalekshmijayakumar/.local/lib/python3.10/site-packages/setuptools/_distutils/cmd.py:66: SetuptoolsDeprecationWarning: setup.py install is deprecated.
!!

        ********************************************************************************
        Please avoid running ``setup.py`` directly.
        Instead, use pypa/build, pypa/installer or other
        standards-based tools.

        See https://blog.ganssle.io/articles/2021/10/setup-py-deprecated.html for details.
        ********************************************************************************

!!
  self.initialize_options()
during RTL pass: ud_dce
In file included from /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp:25,
                 from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp:25,
                 from /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp:18,
                 from /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp:20,
                 from /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp:37,
                 from /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp:25,
                 from /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp:21,
                 from /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp:155,
                 from /home/jayalekshmijayakumar/workspaces/ur_gazebo/install/controller_interface/include/controller_interface/controller_interface_base.hpp:28,
                 from /home/jayalekshmijayakumar/workspaces/ur_gazebo/install/controller_interface/include/controller_interface/chainable_controller_interface.hpp:20,
                 from /home/jayalekshmijayakumar/workspaces/ur_gazebo/src/ros2_control/controller_manager/include/controller_manager/controller_manager.hpp:26,
                 from /home/jayalekshmijayakumar/workspaces/ur_gazebo/src/ros2_control/controller_manager/src/controller_manager.cpp:15:
/opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp: In member function ‘void rclcpp::Subscription<MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>::return_message(std::shared_ptr<void>&) [with MessageT = std_msgs::msg::String_<std::allocator<void> >; AllocatorT = std::allocator<void>; SubscribedT = std_msgs::msg::String_<std::allocator<void> >; ROSMessageT = std_msgs::msg::String_<std::allocator<void> >; MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<std_msgs::msg::String_<std::allocator<void> >, std::allocator<void> >]’:
/opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:402:3: **internal compiler error:** Segmentation fault
  402 |   }
      |   ^
0x7491b064251f ???
	./signal/../sysdeps/unix/sysv/linux/x86_64/libc_sigaction.c:0
Please submit a full bug report,
with preprocessed source if appropriate.
Please include the complete backtrace with any bug report.
See <file:///usr/share/doc/gcc-11/README.Bugs> for instructions.
gmake[2]: *** [CMakeFiles/controller_manager.dir/build.make:76: CMakeFiles/controller_manager.dir/src/controller_manager.cpp.o] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:208: CMakeFiles/controller_manager.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2
---
Failed   <<< controller_manager [14.5s, exited with code 2]
Aborted  <<< moveit_msgs [25.9s]                                    

Summary: 14 packages finished [26.1s]
  1 package failed: controller_manager
  1 package aborted: moveit_msgs
  5 packages had stderr output: controller_manager moveit_configs_utils ros2_controllers_test_nodes rqt_controller_manager rqt_joint_trajectory_controller
  58 packages not processed

I have been getting the following error when building the package using the following command:
colcon build --symlink-install --mixin rel-with-deb-info compile-commands ccache

Robot's joints break on Gazebo

My Environment

  • Ubuntu 22.04.1
  • ROS 2 Humble desktop install

Description

When I start simulation by using ros2 launch ur_simulation_gazebo ur_sim_control.launch.py, the robot's joints break as in this image:
default_gzclient_camera(1)-2022-11-18T18_07_23 988005

To clarify this phenomenon, I changed the initial joint positions as follows:

shoulder_pan_joint: 0.0
shoulder_lift_joint: -1.4
elbow_joint: 2.2
wrist_1_joint: -2.37
wrist_2_joint: -1.57
wrist_3_joint: 0.0

If the controller is not activated, this does not happen (the robot just lies down).

My Attempts

Turning off gravity

I added turnGravityOff tag for each link in the URDF description:

<gazebo reference="shoulder_link">
    <turnGravityOff>true</turnGravityOff>
</gazebo>

Then the robot looks fine, but it may behave the same for external forces other than gravity.

Increasing damping and friction

Increasing the values of damping and friction for each joint in URDF made the robot stable, but the joints still shift a little.

<dynamics damping="1" friction="1"/>

Adding CFM and ERP

I didn't see the effect of this.

<gazebo reference="shoulder_pan_joint">
    <implicitSpringDamper>true</implicitSpringDamper>
    <stopCfm>0</stopCfm>
    <stopErp>0.2</stopErp>
</gazebo>

UR5 controller is shaking

I noticed that when using the simulation with different UR types using ros2 launch ur_simulation_gazebo ur_sim_control.launch.py ur_type:=ur5 all robots work except for UR5 which is weirdly shaking.

Fresh galactic binary build using Universal_Robots_ROS2_Gazebo_Simulation-not-released.galactic.repos (no ros2_control built from source)

Gazebo simulation collapsing

I'm working on Ubuntu 22.04 with Humble and I followed all installation guidelines. Currently, when I launch gazebo, the simulation of the ur5e begins but slowly folds and collapses. It ends up looking like this:

image

The error in the terminal is this:
image
All ros2 control packages are installed properly so I'm not sure why it's saying this.
This is what shows up on rviz:
image
When I run ros2 run joint_state_publisher_gui joint_state_publisher_gui , the robot shows up on rviz:
image

However, the error and faulty gazebo sim still persists. Any help would be much appreciated! I would also like to note that the simulation + rviz did launch properly for me before but I had to uninstall ubuntu and redo the process of setting up the simulation. After redoing it, I am experiencing these issues. I'm not sure what I did differently but are there any dependencies or extra installation steps I'm missing?

Joint_trajectory_controller do not work

Hi, i'm using humble, when i send joint trajectories to the /joint_trajectory_controller/joint_trajectory topic it doesn't work proprerly. No matter the joint config i send it will always go max velocity in the floor, penetrating it and crashing gazebo.
This is the code:
motion.py

import rclpy
from rclpy.node import Node

from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
import trajectory as traj
from std_msgs.msg import Header
from rclpy.duration import Duration
import numpy as np
import kinematics as kin

class PointPublisher(Node):
    def __init__(self):
        super().__init__('point_publisher')
        self.publisher_ = self.create_publisher(JointTrajectory, '/joint_trajectory_controller/joint_trajectory', 10)
        self.q0 = [-1.57, -1.57, -1.57, -1.57, 0, 0]
        

    def publish_point(self, qi, qdi):
        msg = JointTrajectory()
        msg.header = Header()
        msg.joint_names = ['shoulder_pan_joint', 'shoulder_lift_joint', 'elbow_joint', 'wrist_1_joint', 'wrist_2_joint', 'wrist_3_joint']
        
        j = 0
        dj = 0.1
        for i in range(len(qi[0,:])):
            point = JointTrajectoryPoint()
            msg.header.stamp = self.get_clock().now().to_msg()
            joints = qi[:,i].flatten()
            vel = qdi[:,i].flatten()
            point.positions = joints.tolist()
            point.velocities = vel.tolist()
            point.time_from_start = Duration(seconds=j).to_msg()
            j += dj
            msg.points.append(point)
        self.publisher_.publish(msg)
        
    
    def move(self, pos, orientation):
        rotm = kin.eul2Rot(orientation)
        T = np.identity(4)
        T[:3, :3] = rotm
        T[:3, 3] = pos
        possibleQ = kin.inverse_kinematics(T)
        # find closest q to q0
        qf = self.findClosestQ(possibleQ)
        qi, qdi, qddi = traj.cubic_trajectory_planning(self.q0, qf, np.zeros(6), np.zeros(6))
        self.publish_point(qi, qdi)
        # for i in range(len(qi[0,:])):
        #     self.publish_point(qi[:,i].flatten())
        self.q0 = qf
    
    def eucledeanDistance(self, q1, q2):
        return np.linalg.norm(q1 - q2)
    
    def findClosestQ(self, q):
        minDistance = float('inf')
        closestQ = None
        for q_ in q:
            distance = self.eucledeanDistance(self.q0, q_)
            if distance < minDistance:
                minDistance = distance
                closestQ = q_
            
        return closestQ


def main(args=None):
    rclpy.init(args=args)
    pointPub = PointPublisher()
    pointPub.move(np.array([-0.1, -0.1, 0.8]), np.array([0, -1.57, 0]))
    rclpy.spin(pointPub)
    rclpy.shutdown()

if __name__ == '__main__':
    main()

trajectory.py

import numpy as np
import kinematics as kin

def cubic_trajectory_planning(q0 , qf, qd0, qdf, m=100):

    n = len(q0)
    
    a0 = np.copy(q0)
    a1 = np.zeros(n)
    a2 = 3 * (qf - q0) - 2 * qd0 - qdf
    a3 = -2 * (qf - q0) + qd0 + qdf

    timesteps = np.linspace(0, 1, m)

    q = np.zeros((n, m))
    qd = np.zeros((n, m))
    qdd = np.zeros((n, m))

    for i in range(len(timesteps)):
        t = timesteps[i]
        t_2 = t**2
        t_3 = t**3
        q[:, i] = a0 + a1 * t + a2 * t_2 + a3 * t_3
        qd[:, i] = a1 + 2 * a2 * t + 3 * a3 * t_2
        qdd[:, i] = 2 * a2 + 6 * a3 * t

    return q, qd, qdd

def main():
    pos = np.zeros(3)
    rot = np.zeros(3)

    input_pos = input("Enter position: ")
    input_rot = input("Enter rotation: ")

    rotm = kin.eul2Rot(rot)
    T = np.identity(4)
    T[:3, :3] = rotm
    T[:3, 3] = pos

    q0 = np.array([0, 0, 0, 0, 0, 0])
    qf = np.array([1, 1, 1, 1, 1, 1])
    qd0 = np.array([0, 0, 0, 0, 0, 0])
    qdf = np.array([0, 0, 0, 0, 0, 0])
    q, qd, qdd = cubic_trajectory_planning(q0, qf, qd0, qdf)
    print(q[0,:])

if __name__ == '__main__':
    main()

kinematics.py has kin function such as forward kin and inverse one. I'm pretty sure that trajectory and kin are correct. Now i'm not sure that i'm using the trajectory controller in the right way (it's first time).

Gazebo view:
immagine

Rviz view:
immagine

Problems with launching Gazebo simulation

I'm working with Humble ROS2 and Gazebo 11 and followed all instructions in the README. After running colcon build --symlink-install --mixin rel-with-deb-info compile-commands ccache, I sourced my ros2 set up as well as the workspace setup and ran ros2 launch ur_simulation_gazebo ur_sim_control.launch.py. The build compiles all packages successfully but I do get a message at the end that says 3 packages had stderr output: controller_manager joint_trajectory_controller moveit_setup_srdf_plugins. These packages still finished during the build.

I get this error:
ros2 launch ur_simulation_gazebo ur_sim_control.launch.py [INFO] [launch]: All log files can be found below /home/tahira/.ros/log/2023-12-28-22-38-48-759651-tahira-Cyborg-15-A13VE-1196532 [INFO] [launch]: Default logging verbosity is set to INFO [ERROR] [launch]: Caught exception in launch (see debug for traceback): executed command failed. Command: /opt/ros/humble/bin/xacro /home/tre/ws/gaz/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.urdf.xacro safety_limits:=true safety_pos_margin:=0.15 safety_k_position:=20 name:=ur ur_type:=ur5e prefix:="" simulation_controllers:=/home/tre/ws/gaz/install/ur_simulation_gazebo/share/ur_simulation_gazebo/config/ur_controllers.yaml Captured stderr output: error: No such file or directory: /home/tre/ws/gaz/install/ur_description/share/ur_description/urdf/inc/ur_joint_control.xacro [Errno 2] No such file or directory: '/home/tre/ws/gaz/install/ur_description/share/ur_description/urdf/inc/ur_joint_control.xacro' when processing file: /home/tre/ws/gaz/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.ros2_control.xacro included from: /home/tre/ws/gaz/install/ur_simulation_gazebo/share/ur_simulation_gazebo/urdf/ur_gazebo.urdf.xacro
. Is there anything wrong with either how I'm sourcing or build steps? When I go into the install folders for ros2 and for the workspace, I can see the ur_simulation_gazebo folder and launch files so they should exist. Any help will be much appreciated as I am new to Linux and ROS2. Thank you!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.