Misc updates

This commit is contained in:
2023-03-21 08:38:12 +02:00
parent fe8fa8c0cd
commit a71ceb3a90
4 changed files with 14 additions and 4 deletions

View File

@@ -88,6 +88,9 @@ Delimiter characters seem to vary somewhat.
The following examples work: The following examples work:
TODO ADD EXAMPLES OF SVG PATHS TODO ADD EXAMPLES OF SVG PATHS
Make sure that all shapes in the SVG are within the bounds defined by height and width (or viewbox).
Shapes outside of bounds will cause the robot to frequently visit the top left corner and edges of the paper and not draw the desired image.
The following SVG primitives are supported: The following SVG primitives are supported:
| Primitive | Support | | Primitive | Support |
|-------------------------------------|----------| |-------------------------------------|----------|

View File

@@ -1,5 +1,9 @@
# 3D Heatmap in Python using matplotlib # 3D Heatmap in Python using matplotlib
# Script expects a csv consisting of lines in the format:
# success, 10.0 14.2 14.4, 1.0 2.0 3.0, ...
# failure, 10.0 14.2 14.4, 1.0 2.0 3.0, ...
# Usage: python plot_lite6_csv.py OUTPUT.csv
# to make plot interactive # to make plot interactive
#%matplotlib #%matplotlib

View File

@@ -115,7 +115,7 @@ class SVGPathParser():
maxval = np.amax(np.absolute(control_points)) maxval = np.amax(np.absolute(control_points))
#print('maxxv', maxval) #print('maxxv', maxval)
control_points = control_points / maxval #normalize values control_points = control_points / maxval #normalize values
n = 10 n = 50
curve = cf.cubic_curve(control_points) curve = cf.cubic_curve(control_points)
lin = np.linspace(curve.start(0), curve.end(0), n) lin = np.linspace(curve.start(0), curve.end(0), n)
coordinates = curve(lin) coordinates = curve(lin)

View File

@@ -83,7 +83,7 @@ public:
float xlim_upper = 0.305; float xlim_upper = 0.305;
float ylim_lower = -0.1475; float ylim_lower = -0.1475;
float ylim_upper = 0.1475; float ylim_upper = 0.1475;
float zlim_lower = 0.208; float zlim_lower = 0.210;
float zlim_upper = 0.218; float zlim_upper = 0.218;
//bool moved = false; //bool moved = false;
@@ -113,7 +113,10 @@ public:
//command_list_manager = new pilz_industrial_motion_planner::CommandListManager(std::shared_ptr<rclcpp::Node>(std::move(this)), this->move_group.getRobotModel()); //command_list_manager = new pilz_industrial_motion_planner::CommandListManager(std::shared_ptr<rclcpp::Node>(std::move(this)), this->move_group.getRobotModel());
// Use upper joint velocity and acceleration limits // Use upper joint velocity and acceleration limits
this->move_group.setMaxAccelerationScalingFactor(1.0); this->move_group.setMaxAccelerationScalingFactor(1.0);
this->move_group.setMaxVelocityScalingFactor(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);
// Subscribe to target pose // 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)); //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));