You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Which combination of platform is the ROS driver running on.
Ubuntu Linux with standard kernel
How is the UR ROS2 Driver installed.
Build the driver from source and using the UR Client Library from binary
Which robot platform is the driver connected to.
Real robot
Robot SW / URSim version(s)
ur5
How is the ROS driver used.
Others
Issue details
When i run the moveit support package for this driver through:
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5 launch_rviz:=true
i get this warning
[WARN] [1731009987.767804840] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
However this is not a problem when controlling the robot through the rviz gui using moveit.
The problem arises when im trying to run my own move_group node in parallel with the ur_moveit_config package. i get this error when trying to use Inverse kinematics for setting joint value targets from poses in cartesian space.
[ERROR] [1731009989.969819875] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'ur_manipulator'
I used the move group interface tutorial to build my custom node.
These are the changes i made to the ur_moveit.launch.py:
i added this code to the launch_setup in ur_moveit.launch.py
Here is a snippet of my custom move_group_reciever node:
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::NodeOptions node_options;
node_options.automatically_declare_parameters_from_overrides(true);
auto move_group_reciever = std::make_shared();
// Single-threaded executor for the robot state monitor
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(move_group_reciever);
std::thread([&executor]() { executor.spin(); }).detach();
// Set the planning group for UR manipulator
static const std::string PLANNING_GROUP = "ur_manipulator";
// Initialize MoveGroupInterface with UR manipulator planning group
moveit::planning_interface::MoveGroupInterface move_group(move_group_reciever, PLANNING_GROUP);
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
const moveit::core::JointModelGroup* joint_model_group = move_group.getCurrentState()->getJointModelGroup(PLANNING_GROUP);
// Visualization setup
namespace rvt = rviz_visual_tools;
moveit_visual_tools::MoveItVisualTools visual_tools(move_group_reciever, "world", "/display_planned_path",
move_group.getRobotModel());
visual_tools.deleteAllMarkers();
visual_tools.loadRemoteControl();
Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity();
text_pose.translation().z() = 0.5;
visual_tools.publishText(text_pose, "UR Manipulator Demo", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
// Display basic information about the robot
RCLCPP_INFO(LOGGER, "Planning frame: %s", move_group.getPlanningFrame().c_str());
RCLCPP_INFO(LOGGER, "End effector link: %s", move_group.getEndEffectorLink().c_str());
RCLCPP_INFO(LOGGER, "Available Planning Groups:");
std::copy(move_group.getJointModelGroupNames().begin(), move_group.getJointModelGroupNames().end(),
std::ostream_iterator<std::string>(std::cout, ", "));
// Wait for the subscriber to receive the first message
rclcpp::sleep_for(std::chrono::seconds(1)); // Allow time for the subscriber to process
// // Plan and visualize
moveit::planning_interface::MoveGroupInterface::Plan my_plan;
moveit_msgs::msg::CollisionObject object_to_attach;
object_to_attach.id = "cylinder1";
shape_msgs::msg::SolidPrimitive primitive;
shape_msgs::msg::SolidPrimitive cylinder_primitive;
cylinder_primitive.type = primitive.CYLINDER;
cylinder_primitive.dimensions.resize(2);
cylinder_primitive.dimensions[primitive.CYLINDER_HEIGHT] = 0.25;
cylinder_primitive.dimensions[primitive.CYLINDER_RADIUS] = 0.06;
object_to_attach.header.frame_id = move_group.getEndEffectorLink();
geometry_msgs::msg::Pose grab_pose;
grab_pose.orientation.w = 1.0;
grab_pose.position.z = 0.103 - 0.135;
object_to_attach.primitives.push_back(cylinder_primitive);
object_to_attach.primitive_poses.push_back(grab_pose);
object_to_attach.operation = object_to_attach.ADD;
planning_scene_interface.applyCollisionObject(object_to_attach);
RCLCPP_INFO(LOGGER, "Attach the object to the robot");
std::vector<std::string> touch_links;
touch_links.push_back("tool0");
touch_links.push_back("wrist_3_link");
move_group.attachObject(object_to_attach.id, "tool0", touch_links);
visual_tools.publishText(text_pose, "Object_attached_to_robot", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
moveit_msgs::msg::CollisionObject collision_object;
collision_object.header.frame_id = move_group.getEndEffectorLink();
collision_object.id = "box1";
primitive.type = primitive.BOX;
primitive.dimensions.resize(3);
primitive.dimensions[primitive.BOX_X] = 0.15;
primitive.dimensions[primitive.BOX_Y] = 0.04;
primitive.dimensions[primitive.BOX_Z] = 0.04;
geometry_msgs::msg::Pose grab_pose1;
grab_pose1.orientation.w = 1.0;
grab_pose1.position.y = -0.08;
grab_pose1.position.z = -0.064-0.135;
collision_object.primitives.push_back(primitive);
collision_object.primitive_poses.push_back(grab_pose1);
collision_object.operation = object_to_attach.ADD;
planning_scene_interface.applyCollisionObject(collision_object);
RCLCPP_INFO(LOGGER, "Attach the object to the robot");
std::vector<std::string> touch_links1;
//touch_links.push_back("");
touch_links1.push_back("wrist_2_link");
touch_links1.push_back("wrist_3_link");
move_group.attachObject(collision_object.id, "wrist_2_link", touch_links1);
visual_tools.publishText(text_pose, "Object_attached_to_robot", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
/* Wait for MoveGroup to receive and process the attached collision object message */
//visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window once the new object is attached to the robot");
moveit::core::RobotStatePtr current_state = move_group.getCurrentState(10);
std::vector<double> joint_group_positions;
current_state->copyJointGroupPositions(joint_model_group, joint_group_positions);
joint_group_positions[0] = 1.536;
joint_group_positions[1] = -2.356;
joint_group_positions[2] = 2.356;
joint_group_positions[3] = -3.141;
joint_group_positions[4] = -1.606;
joint_group_positions[5] = 0; // Modify this for UR robot
bool within_bounds = move_group.setJointValueTarget(joint_group_positions);
if (!within_bounds)
{
RCLCPP_WARN(LOGGER, "Target joint position(s) were outside of limits, but will be clamped.");
}
move_group.setMaxVelocityScalingFactor(0.1);
move_group.setMaxAccelerationScalingFactor(0.1);
bool success = (move_group.plan(my_plan) == moveit::core::MoveItErrorCode::SUCCESS);
RCLCPP_INFO(LOGGER, "Visualizing plan (joint-space goal) %s", success ? "" : "FAILED");
visual_tools.deleteAllMarkers();
visual_tools.publishText(text_pose, "Joint Space Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);
visual_tools.trigger();
//visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");
move_group.move();
moveit_msgs::msg::OrientationConstraint ocm;
ocm.link_name = "wrist_2_link";
ocm.header.frame_id = "base_link";
ocm.orientation.w = 0.999;
ocm.absolute_x_axis_tolerance = 0.1;
ocm.absolute_y_axis_tolerance = 0.1;
ocm.absolute_z_axis_tolerance = 0.1;
ocm.weight = 1.0;
moveit_msgs::msg::Constraints test_constraints;
test_constraints.orientation_constraints.push_back(ocm);
move_group.setPathConstraints(test_constraints);
rclcpp::sleep_for(std::chrono::seconds(1)); // Allow time for the subscriber to process
//Get the target pose after the first message is received
// geometry_msgs::msg::Pose target_pose1 = move_group_reciever->getTargetPose();
geometry_msgs::msg::Pose target_pose1;
target_pose1.position.x = -0.400;
target_pose1.position.y = 0.546;
target_pose1.position.z = 0.564;
target_pose1.orientation.x = -0.707;
target_pose1.orientation.y = 0.025;
target_pose1.orientation.z = -0.025;
target_pose1.orientation.w = 0.706;
target_pose1.position.y -= 0.10;
move_group.setStartStateToCurrentState();
move_group.setPoseTarget(target_pose1);
//move_group.setPlanningTime(10.0);
RCLCPP_INFO(LOGGER, "Planning frame: %s", move_group.getPlanningFrame().c_str());
success = (move_group.plan(my_plan) == moveit::core::MoveItErrorCode::SUCCESS);
RCLCPP_INFO(LOGGER, "Visualizing plan (pose goal) %s", success ? "" : "FAILED");
visual_tools.publishAxisLabeled(target_pose1, "pose1");
visual_tools.publishText(text_pose, "Pose Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);
visual_tools.trigger();
//visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");
move_group.move();
move_group.setPlannerId("RRTConnectkConfigDefault");
target_pose1.position.y += 0.10;
move_group.setStartStateToCurrentState();
move_group.setJointValueTarget(target_pose1);
RCLCPP_INFO(LOGGER, "Planning frame: %s", move_group.getPlanningFrame().c_str());
success = (move_group.plan(my_plan) == moveit::core::MoveItErrorCode::SUCCESS);
RCLCPP_INFO(LOGGER, "Visualizing plan (pose goal) %s", success ? "" : "FAILED");
visual_tools.publishAxisLabeled(target_pose1, "pose1");
visual_tools.publishText(text_pose, "Pose Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);
visual_tools.trigger();
//visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo");
move_group.move();
everything runs well until this line
move_group.setJointValueTarget(target_pose1);
Here i get the error as described above.
[ERROR] [1731009989.969819875] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'ur_manipulator'
Relevant log output
ros2 run moving_ur5 move_group_reciever
Error: Semantic description is not specified for the same robot as the URDF
at line 681 in ./src/model.cpp
[INFO] [1731009987.757296570] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 1.00248 seconds
[INFO] [1731009987.757366073] [moveit_robot_model.robot_model]: Loading robot model 'ur5'...
[INFO] [1731009987.757377686] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[WARN] [1731009987.767804840] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[INFO] [1731009987.783556789] [move_group_interface]: Ready to take commands for planning group ur_manipulator.
[INFO] [1731009987.792918751] [moveit_ros.current_state_monitor]: Listening to joint states on topic 'joint_states'
[INFO] [1731009987.794529218] [move_group_reciever.remote_control]: RemoteControl Ready.
[INFO] [1731009987.796421294] [move_group_demo]: Planning frame: world
[INFO] [1731009987.796440631] [move_group_demo]: End effector link: virtual_jaw_edge
[INFO] [1731009987.796448176] [move_group_demo]: Available Planning Groups:
[INFO] [1731009988.797445482] [move_group_demo]: Attach the object to the robot
[INFO] [1731009988.798136686] [move_group_demo]: Attach the object to the robot
[INFO] [1731009988.801814975] [move_group_interface]: MoveGroup action client/server ready
[INFO] [1731009988.802265950] [move_group_interface]: Planning request accepted
[INFO] [1731009988.939662481] [move_group_interface]: Planning request complete!
[INFO] [1731009988.940359406] [move_group_interface]: time taken to generate plan: 0.0171973 seconds
[INFO] [1731009988.940396738] [move_group_demo]: Visualizing plan (joint-space goal)
[INFO] [1731009988.940841671] [move_group_interface]: Plan and Execute request accepted
[INFO] [1731009988.946121148] [move_group_interface]: Plan and Execute request complete!
[INFO] [1731009989.947126059] [move_group_demo]: Planning frame: world
[INFO] [1731009989.947294813] [move_group_interface]: MoveGroup action client/server ready
[INFO] [1731009989.947716380] [move_group_interface]: Planning request accepted
[INFO] [1731009989.954573410] [move_group_interface]: Planning request aborted
[ERROR] [1731009989.954851102] [move_group_interface]: MoveGroupInterface::plan() failed or timeout reached
[INFO] [1731009989.954882202] [move_group_demo]: Visualizing plan (pose goal) FAILED
[INFO] [1731009989.955369545] [move_group_interface]: Plan and Execute request accepted
[INFO] [1731009989.962616231] [move_group_interface]: Plan and Execute request aborted
[ERROR] [1731009989.963635134] [move_group_interface]: MoveGroupInterface::move() failed or timeout reached
[ERROR] [1731009989.969819875] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'ur_manipulator'
[INFO] [1731009989.969840915] [move_group_demo]: Planning frame: world
[INFO] [1731009989.969941488] [move_group_interface]: MoveGroup action client/server ready
[INFO] [1731009989.970181568] [move_group_interface]: Planning request accepted
[INFO] [1731009990.006926647] [move_group_interface]: Planning request complete!
[INFO] [1731009990.007973022] [move_group_interface]: time taken to generate plan: 0.0234684 seconds
[INFO] [1731009990.008015313] [move_group_demo]: Visualizing plan (pose goal)
[INFO] [1731009990.008534568] [move_group_interface]: Plan and Execute request accepted
[INFO] [1731009990.010111760] [move_group_interface]: Plan and Execute request complete!
Accept Public visibility
I agree to make this context public
The text was updated successfully, but these errors were encountered:
Affected ROS2 Driver version(s)
Humble
Used ROS distribution.
Humble
Which combination of platform is the ROS driver running on.
Ubuntu Linux with standard kernel
How is the UR ROS2 Driver installed.
Build the driver from source and using the UR Client Library from binary
Which robot platform is the driver connected to.
Real robot
Robot SW / URSim version(s)
ur5
How is the ROS driver used.
Others
Issue details
When i run the moveit support package for this driver through:
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5 launch_rviz:=true
i get this warning
[WARN] [1731009987.767804840] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
However this is not a problem when controlling the robot through the rviz gui using moveit.
The problem arises when im trying to run my own move_group node in parallel with the ur_moveit_config package. i get this error when trying to use Inverse kinematics for setting joint value targets from poses in cartesian space.
[ERROR] [1731009989.969819875] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'ur_manipulator'
I used the move group interface tutorial to build my custom node.
These are the changes i made to the ur_moveit.launch.py:
i added this code to the launch_setup in ur_moveit.launch.py
Here is a snippet of my custom move_group_reciever node:
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::NodeOptions node_options;
node_options.automatically_declare_parameters_from_overrides(true);
auto move_group_reciever = std::make_shared();
everything runs well until this line
Here i get the error as described above.
[ERROR] [1731009989.969819875] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'ur_manipulator'
Relevant log output
Accept Public visibility
The text was updated successfully, but these errors were encountered: