Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Issue 304 #305

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
87 changes: 53 additions & 34 deletions iiwa_moveit/launch/moveit.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,19 @@ Panels:
Property Tree Widget:
Expanded:
- /MotionPlanning1
- /MotionPlanning1/Status1
Splitter Ratio: 0.74256
Tree Height: 532
Splitter Ratio: 0.7425600290298462
Tree Height: 367
- Class: rviz/Help
Name: Help
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
Expand All @@ -24,7 +27,7 @@ Visualization Manager:
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.03
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Expand All @@ -36,17 +39,31 @@ Visualization Manager:
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: moveit_rviz_plugin/MotionPlanning
- Acceleration_Scaling_Factor: 0.1
Class: moveit_rviz_plugin/MotionPlanning
Enabled: true
Move Group Namespace: ""
MoveIt_Goal_Tolerance: 0
MoveIt_Allow_Approximate_IK: false
MoveIt_Allow_External_Program: false
MoveIt_Allow_Replanning: false
MoveIt_Allow_Sensor_Positioning: false
MoveIt_Planning_Attempts: 10
MoveIt_Planning_Time: 5
MoveIt_Use_Cartesian_Path: true
MoveIt_Use_Constraint_Aware_IK: true
MoveIt_Warehouse_Host: 127.0.0.1
MoveIt_Warehouse_Port: 33829
MoveIt_Workspace:
Center:
X: 0
Y: 0
Z: 0
Size:
X: 2
Y: 2
Z: 2
Name: MotionPlanning
Planned Path:
Color Enabled: false
Interrupt Display: false
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Down Expand Up @@ -97,28 +114,27 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
world:
Alpha: 1
Show Axes: false
Show Trail: false
Loop Animation: true
Loop Animation: false
Robot Alpha: 0.5
Robot Color: 150; 50; 150
Show Robot Collision: false
Show Robot Visual: true
Show Trail: false
State Display Time: 0.05 s
Trail Step Size: 1
Trajectory Topic: move_group/display_planned_path
Use Sim Time: false
Planning Metrics:
Payload: 1
Show Joint Torques: false
Show Manipulability: false
Show Manipulability Index: false
Show Weight Limit: false
TextHeight: 0.08
TextHeight: 0.07999999821186066
Planning Request:
Colliding Link Color: 255; 0; 0
Goal State Alpha: 1
Expand All @@ -136,7 +152,7 @@ Visualization Manager:
Scene Geometry:
Scene Alpha: 1
Scene Color: 50; 230; 50
Scene Display Time: 0.2
Scene Display Time: 0.20000000298023224
Show Scene Geometry: true
Voxel Coloring: Z-Axis
Voxel Rendering: Occupied Voxels
Expand Down Expand Up @@ -192,10 +208,6 @@ Visualization Manager:
Alpha: 1
Show Axes: false
Show Trail: false
tool0:
Alpha: 1
Show Axes: false
Show Trail: false
world:
Alpha: 1
Show Axes: false
Expand All @@ -204,9 +216,11 @@ Visualization Manager:
Show Robot Collision: false
Show Robot Visual: true
Value: true
Velocity_Scaling_Factor: 0.1
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: world
Frame Rate: 30
Name: root
Expand All @@ -219,36 +233,41 @@ Visualization Manager:
Views:
Current:
Class: rviz/XYOrbit
Distance: 3.34699
Distance: 3.3469901084899902
Enable Stereo Rendering:
Stereo Eye Separation: 0.06
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.113567
Y: 0.10592
Z: 2.23518e-07
X: 0.11356700211763382
Y: 0.10592000186443329
Z: 2.2351800055275817e-07
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.01
Pitch: 0.359797
Near Clip Distance: 0.009999999776482582
Pitch: 0.8497965335845947
Target Frame: world
Value: XYOrbit (rviz)
Yaw: 5.67496
Yaw: 3.7849502563476562
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1138
Height: 1016
Help:
collapsed: false
Hide Left Dock: false
Hide Right Dock: false
Motion Planning:
MotionPlanning:
collapsed: false
MotionPlanning - Trajectory Slider:
collapsed: false
QMainWindow State: 000000ff00000000fd0000000100000000000002a200000422fc0200000005fb000000100044006900730070006c0061007900730100000033000002a5000000d801000005fb0000000800480065006c00700000000342000000bb0000007101000005fb0000000a0056006900650077007300000003b0000000b0000000ab01000005fb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000002db0000017a00000171010000050000047f0000042200000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000100000000000002a20000039efc0200000007fb000000100044006900730070006c006100790073010000003d00000200000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a0056006900650077007300000003b0000000b0000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e006701000002db0000017a0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000243000001980000017d00ffffff000004a80000039e00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Views:
collapsed: false
Width: 1828
X: 88
Y: 0
Width: 1872
X: 48
Y: 27
5 changes: 3 additions & 2 deletions iiwa_ros/src/service/path_parameters_lin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace service {
void PathParametersLinService::init(const std::string& robot_namespace) {
setup(robot_namespace);
ros::NodeHandle node_handle{};
service_name_ = ros_namespace_ + "configuration/setSmartServoLinSpeedLimits";
service_name_ = ros_namespace_ + "configuration/setSmartServoLinLimits";
client_ = node_handle.serviceClient<iiwa_msgs::SetSmartServoLinSpeedLimits>(service_name_);
service_ready_ = true;
}
Expand All @@ -48,7 +48,7 @@ bool PathParametersLinService::callService() {
service_error_ = config_.response.error;
ROS_ERROR_STREAM(service_name_ << " failed, Java error: " << service_error_);
} else if (verbose_) {
ROS_INFO_STREAM(ros::this_node::getName() << ":" << service_name_ << " successfully called.");
ROS_INFO_STREAM(ros::this_node::getName() << ": " << service_name_ << " successfully called.");
}
} else if (verbose_) {
ROS_ERROR_STREAM(service_name_ << " could not be called");
Expand All @@ -60,6 +60,7 @@ bool PathParametersLinService::callService() {

bool PathParametersLinService::setMaxCartesianVelocity(const geometry_msgs::Twist max_cartesian_velocity) {
config_.request.max_cartesian_velocity = max_cartesian_velocity;
return callService();
}

} // namespace service
Expand Down