-
Notifications
You must be signed in to change notification settings - Fork 21
Replies: 3 comments · 5 replies
-
This reads like a similar issue as was reported in #233. Could you please look at my comment there and provide your information in that thread? |
Beta Was this translation helpful? Give feedback.
All reactions
-
Sure: motoros2_config.yaml Click to expandagent_ip_address: 172.17.47.10
agent_port_number: 8888
ros_domain_id: 1
node_name: "yrc_1000_micro"
node_namespace: "moto_gp4"
sync_timeclock_with_agent: true
stop_motion_on_disconnect: true
publish_tf: false
namespace_tf: true
joint_names:
- [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
logging:
log_to_stdout: false
update_periods:
executor_sleep_period: 10
feedback_publisher_period: 20
controller_io_status_monitor_period: 10
publisher_qos:
robot_status: sensor_data
joint_states: default
tf: default Example of a Click to expand#include <memory>
#include "std_srvs/srv/trigger.hpp"
#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>
#include <rclcpp/rclcpp.hpp>
#include <moveit/moveit_cpp/moveit_cpp.h>
#include <moveit/moveit_cpp/planning_component.h>
#include <chrono>
#include <thread>
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto const node = std::make_shared<rclcpp::Node>(
"hello_moveit", rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));
// Create a ROS logger
auto const logger = rclcpp::get_logger("hello_moveit");
// Create the MoveIt MoveGroup Interface
using moveit::planning_interface::MoveGroupInterface;
auto move_group_interface = MoveGroupInterface(node, "manipulator");
move_group_interface.setPlanningPipelineId("pilz_industrial_motion_planner");
move_group_interface.setPlannerId("LIN");
move_group_interface.setGoalTolerance(0.01);
move_group_interface.setMaxAccelerationScalingFactor(0.1);
move_group_interface.setMaxVelocityScalingFactor(0.1);
//==========================================================
// Set a target Pose
auto const target_pose = []
{
geometry_msgs::msg::Pose msg;
msg.orientation.x = 0.70714;
msg.orientation.y = 0.707073;
msg.orientation.z = 0.0;
msg.orientation.w = 0.0;
msg.position.x = 0.116045;
msg.position.y = -0.235879;
msg.position.z = 0.55;
return msg;
}();
move_group_interface.setPoseTarget(target_pose);
// Create a plan to that target pose
auto const [success, plan] = [&move_group_interface]
{
moveit::planning_interface::MoveGroupInterface::Plan msg;
auto const ok = static_cast<bool>(move_group_interface.plan(msg));
return std::make_pair(ok, msg);
}();
// Execute the plan
if (success)
{
RCLCPP_INFO(logger, "Planning OK!");
RCLCPP_INFO(logger, "Bestätigen das Trajektorie ausgeführt wurde");
std::cin.get();
move_group_interface.execute(plan);
}
else
{
RCLCPP_ERROR(logger, "Planning failed!");
}
//==========================================================
// Set a target Pose
auto const target_pose2 = []
{
geometry_msgs::msg::Pose msg;
msg.orientation.x = 1.0;
msg.orientation.y = 0.0;
msg.orientation.z = 0.0;
msg.orientation.w = 0.0;
msg.position.x = 0.3;
msg.position.y = 0.0;
msg.position.z = 0.55;
return msg;
}();
move_group_interface.setPoseTarget(target_pose2);
// Create a plan to that target pose
auto const [success2, plan2] = [&move_group_interface]
{
moveit::planning_interface::MoveGroupInterface::Plan msg;
auto const ok = static_cast<bool>(move_group_interface.plan(msg));
return std::make_pair(ok, msg);
}();
// Execute the plan
if (success2)
{
RCLCPP_INFO(logger, "Planning OK!");
RCLCPP_INFO(logger, "Bestätigen das Trajektorie ausgeführt wurde");
std::cin.get();
move_group_interface.execute(plan2);
}
else
{
RCLCPP_ERROR(logger, "Planning failed!");
}
//==========================================================
// Shutdown ROS
rclcpp::shutdown();
return 0;
} If required, I can also provide my entire Moveit configuration. The launch file for moveit is in my message above. Full debug log from control start to the finished execution of the test script: Click to expand
Motors2 version & ROS2 distribution: Robot Controller & Robot: |
Beta Was this translation helpful? Give feedback.
All reactions
-
@TE-2: thanks for the additional information. Please see #233 for the ongoing discussion and discovery. It's possible your trajectories don't actually provide any |
Beta Was this translation helpful? Give feedback.
All reactions
-
👍 1
-
okay thanks for the quick response! |
Beta Was this translation helpful? Give feedback.
All reactions
-
@gavanderhoorn |
Beta Was this translation helpful? Give feedback.
All reactions
-
It would indeed be a good idea to verify I'm still not sure why this would suddenly be a problem, but let's be pragmatic. |
Beta Was this translation helpful? Give feedback.
All reactions
-
I would not expect these to be related, as the check you report and the error emitted is on the Yaskawa controller side. The problem with your As you've reported issues with your MoveIt configuration(s) in #225, I would currently expect it to be an issue with your setup there. |
Beta Was this translation helpful? Give feedback.
All reactions
-
👍 1
-
all right, then I'll take a closer look at the moveit config again. |
Beta Was this translation helpful? Give feedback.
-
Hello,
I have a Yaskawa GP4 in combination with a YRC1000micro. I'm using the ros2-starter-for-yaskawa-robots repository and adapted the ros2 package motoXY to the GP4 using the robot descriptions from the ros-industrial motoman repo and so far everything is working.
I also changed the joint names in the motoros2_config.yaml to
- [joint_1, joint_2, joint_3, joint_4, joint_5, joint_6]
and also adapted this change in the moveit configurations.I then used
hello_moveit.cpp
to execute the first trajectories and it worked.My launch file to start the move group node looks like this:
Click to expand
However, despite the trajectory being executed correctly, I always get the following error in the terminal of my hello_moveit.cpp script:
When I look at the logs of the terminal of my move_group node, I get the following:
The message indicates that the goal deviations for the individual joints are set to 0.0. I'm not sure about the safety limits, but I think the robot trajectories are not interrupted or interfered with by any limits. So I edited the hello_moveit script a bit and added a goal tolerance before planning and executing the trajectory:
move_group_interface.setGoalTolerance(0.01);
Which I can also validate via the following methods:
However, setting the GoalTolerance had no effect..
I've also looked in the
moto_description
andmoveit_configuration
to see if I can adjust anything there, but unfortunately I couldn't find anything that indicated goal tolerances or safety limits.I have also noticed that I have problems when calling
getCurrentJointValues
orgetCurrentPose
:Click to expand
But I'm not sure if these Problems are related or have any influence on each other.
I am currently ignoring a failed execution of the trajectory, but this involves critical sources of error.
I'm using version 0.1.2 of motoros2 and the ROS2 distribution Humble.
I would appreciate any helpful input.
Thanks
Beta Was this translation helpful? Give feedback.
All reactions