Set new parameters for xArm
This commit is contained in:
@@ -1,5 +1,5 @@
|
||||
cartesian_limits:
|
||||
max_trans_vel: 2.0
|
||||
max_trans_acc: 3.00
|
||||
max_trans_vel: 0.4
|
||||
max_trans_acc: 4.00
|
||||
max_trans_dec: -5.0
|
||||
max_rot_vel: 1.57
|
||||
|
||||
@@ -4,31 +4,31 @@
|
||||
joint_limits:
|
||||
joint1:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
joint2:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
joint3:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
joint4:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
joint5:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
joint6:
|
||||
has_velocity_limits: true
|
||||
max_velocity: 10.14
|
||||
max_velocity: 4.14
|
||||
has_acceleration_limits: true
|
||||
max_acceleration: 20.0
|
||||
max_acceleration: 30.0
|
||||
|
||||
@@ -115,7 +115,7 @@ class SVGPathParser():
|
||||
maxval = np.amax(np.absolute(control_points))
|
||||
#print('maxxv', maxval)
|
||||
#control_points = control_points / maxval #normalize values
|
||||
n = 1000
|
||||
n = 100
|
||||
curve = cf.bezier(control_points)
|
||||
lin = np.linspace(curve.start(0), curve.end(0), n)
|
||||
coordinates = curve(lin)
|
||||
@@ -140,7 +140,7 @@ class SVGPathParser():
|
||||
nonlocal x
|
||||
nonlocal y
|
||||
control_points = np.array(control_points)
|
||||
n = 1000
|
||||
n = 100
|
||||
curve = cf.bezier(control_points, quadratic=True)
|
||||
lin = np.linspace(curve.start(0), curve.end(0), n)
|
||||
coordinates = curve(lin)
|
||||
|
||||
@@ -197,8 +197,8 @@ class SVGProcessor():
|
||||
Simplify line with https://pypi.org/project/simplification/
|
||||
"""
|
||||
# For RDP, Try an epsilon of 1.0 to start with. Other sensible values include 0.01, 0.001
|
||||
#epsilon = 0.009
|
||||
epsilon = 0.00005
|
||||
#epsilon = 0.00005
|
||||
epsilon = 0.0008
|
||||
|
||||
tmp = []
|
||||
out = []
|
||||
|
||||
@@ -198,11 +198,11 @@ public:
|
||||
//mpr.planner_id = "LIN";
|
||||
mpr.group_name = move_group.getName();
|
||||
//mpr.max_velocity_scaling_factor = 1.0;
|
||||
mpr.max_velocity_scaling_factor = 0.3;
|
||||
mpr.max_acceleration_scaling_factor = 0.3;
|
||||
mpr.max_velocity_scaling_factor = 1.0;
|
||||
mpr.max_acceleration_scaling_factor = 1.0;
|
||||
//mpr.max_acceleration_scaling_factor = 0.1;
|
||||
mpr.allowed_planning_time = 20;
|
||||
mpr.max_cartesian_speed = 3; // m/s
|
||||
//mpr.max_cartesian_speed = 2; // m/s
|
||||
//mpr.goal_constraints.position_constraints.header.frame_id = "world";
|
||||
|
||||
// A tolerance of 0.01 m is specified in position
|
||||
@@ -368,8 +368,17 @@ public:
|
||||
|
||||
void executeTrajectoryFromQueue()
|
||||
{
|
||||
if (busy || trajectory_queue.empty())
|
||||
if (trajectory_queue.empty())
|
||||
{
|
||||
if (busy)
|
||||
return;
|
||||
|
||||
busy = true;
|
||||
//RCLCPP_INFO(this->get_logger(), "Getting robot state");
|
||||
//move_group_state = move_group.getCurrentState(10);
|
||||
busy = false;
|
||||
return;
|
||||
}
|
||||
busy = true;
|
||||
RCLCPP_INFO(this->get_logger(), "Executing next trajectory from queue");
|
||||
move_group.execute(trajectory_queue.front());
|
||||
|
||||
Reference in New Issue
Block a user