Tune parameters

This commit is contained in:
2023-03-28 17:35:59 +03:00
parent c5761dc8e8
commit 6d6f2aa393
5 changed files with 15 additions and 15 deletions

View File

@@ -4,31 +4,31 @@
joint_limits:
joint1:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0
joint2:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0
joint3:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0
joint4:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0
joint5:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0
joint6:
has_velocity_limits: true
max_velocity: 3.14
max_velocity: 10.14
has_acceleration_limits: true
max_acceleration: 20.0

View File

@@ -198,7 +198,7 @@ class SVGProcessor():
"""
# For RDP, Try an epsilon of 1.0 to start with. Other sensible values include 0.01, 0.001
#epsilon = 0.009
epsilon = 0.005
epsilon = 0.0005
tmp = []
out = []

View File

@@ -89,8 +89,8 @@ public:
float xlim_upper = 0.305;
float ylim_lower = -0.1475;
float ylim_upper = 0.1475;
float zlim_lower = 0.210;
float zlim_upper = 0.218;
float zlim_lower = 0.1945;
float zlim_upper = 0.200;
//bool moved = false;
//
@@ -121,8 +121,8 @@ public:
this->move_group.setMaxAccelerationScalingFactor(1.0);
//setting this lower seems to improve overall time and prevents robot from moving too fast
//this->move_group.setMaxVelocityScalingFactor(1.0);
this->move_group.setMaxVelocityScalingFactor(0.8);
this->move_group.setMaxVelocityScalingFactor(1.0);
//this->move_group.setMaxVelocityScalingFactor(0.8);
// Subscribe to target pose
//target_pose_sub_ = this->create_subscription<geometry_msgs::msg::PoseStamped>("/target_pose", rclcpp::QoS(1), std::bind(&MoveItFollowTarget::target_pose_callback, this, std::placeholders::_1));
@@ -237,7 +237,7 @@ public:
mpr.planner_id = "LIN";
mpr.group_name = move_group.getName();
//mpr.max_velocity_scaling_factor = 1.0;
mpr.max_velocity_scaling_factor = 0.7;
mpr.max_velocity_scaling_factor = 0.3;
mpr.max_acceleration_scaling_factor = 0.4;
//mpr.max_acceleration_scaling_factor = 0.1;
mpr.allowed_planning_time = 10;

View File

@@ -73,7 +73,7 @@ class DrawingApp(tk.Tk):
def draw(self,x,y,z):
# putpixel is too slow
#self.img.putpixel((int(x), int(y)), (255, 0, 0))
r = 4 # radius
r = 3 # radius
for xp in range(max(0, x-r), min(self.width-1, x+r)):
for yp in range(max(0, y-r), min(self.height-1, y+r)):
self.arr[xp,yp,0] = 0 #red
@@ -105,7 +105,7 @@ class DrawingApp(tk.Tk):
#y = translate(p.y, -0.51, -0.3, 0, self.height)
x = int(translate(p.y, -0.5, 0.5, 0, self.width))
y = int(translate(p.x, -0.3485, 0.1, 0, self.height))
y = int(translate(p.x, -0.2485, 0.1, 0, self.height))
#x = bound(self.width - x, 0, self.width)
#y = bound(self.height - y, 0, self.height)