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

Add param for vel scaling of the scan movement #240

Open
wants to merge 1 commit into
base: kinetic-devel
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions godel_msgs/msg/RobotScanParameters.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# path planning
string group_name
float64 move_scan_vel_scaling
string home_position
string world_frame
string tcp_frame
Expand Down
2 changes: 2 additions & 0 deletions godel_plugins/src/widgets/robot_scan_configuration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ void godel_plugins::RobotScanConfigWidget::update_gui_fields()
ui_.LineEditWorldFrame->setText(QString::fromStdString(params_.world_frame));
ui_.LineEditTcpFrame->setText(QString::fromStdString(params_.tcp_frame));
ui_.LineEditGroupName->setText(QString::fromStdString(params_.group_name));
ui_.LineEditMoveScanVelScaling->setText(QString::number(params_.move_scan_vel_scaling));
ui_.CheckBoxStopOnPlanningError->setChecked(params_.stop_on_planning_error);

world_to_obj_pose_widget_->set_values(params_.world_to_obj_pose);
Expand All @@ -102,6 +103,7 @@ void godel_plugins::RobotScanConfigWidget::update_internal_values()
params_.world_frame = ui_.LineEditWorldFrame->text().toStdString();
params_.tcp_frame = ui_.LineEditTcpFrame->text().toStdString();
params_.group_name = ui_.LineEditGroupName->text().toStdString();
params_.move_scan_vel_scaling = ui_.LineEditMoveScanVelScaling->text().toDouble();
params_.stop_on_planning_error = ui_.CheckBoxStopOnPlanningError->isChecked();

tf::poseTFToMsg(world_to_obj_pose_widget_->get_values(), params_.world_to_obj_pose);
Expand Down
31 changes: 27 additions & 4 deletions godel_plugins/src/widgets/robot_scan_configuration.ui
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>540</width>
<height>563</height>
<height>583</height>
</rect>
</property>
<property name="font">
Expand Down Expand Up @@ -105,7 +105,7 @@
<x>30</x>
<y>40</y>
<width>281</width>
<height>441</height>
<height>461</height>
</rect>
</property>
<property name="frameShape">
Expand Down Expand Up @@ -299,13 +299,36 @@
</widget>
</item>
<item row="12" column="0">
<widget class="QLabel" name="moveScanVelScalingLabel">
<property name="text">
<string>Move Scan Vel Scaling</string>
</property>
</widget>
</item>
<item row="12" column="1">
<widget class="QLineEdit" name="LineEditMoveScanVelScaling">
<property name="inputMethodHints">
<set>Qt::ImhDigitsOnly</set>
</property>
<property name="inputMask">
<string/>
</property>
<property name="text">
<string/>
</property>
<property name="maxLength">
<number>8</number>
</property>
</widget>
</item>
<item row="13" column="0">
<widget class="QLabel" name="stopOnPlanningErrorLabel">
<property name="text">
<string>Stop On Plan Error</string>
</property>
</widget>
</item>
<item row="12" column="1">
<item row="13" column="1">
<widget class="QCheckBox" name="CheckBoxStopOnPlanningError"/>
</item>
</layout>
Expand Down Expand Up @@ -341,7 +364,7 @@
<property name="geometry">
<rect>
<x>33</x>
<y>500</y>
<y>520</y>
<width>491</width>
<height>33</height>
</rect>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
robot_scan:
group_name: manipulator_asus
move_scan_vel_scaling: 1
home_position: home_asus
world_frame: world_frame
tcp_frame: kinect2_move_frame
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
robot_scan:
group_name: manipulator_asus
move_scan_vel_scaling: 1
home_position: home_asus
world_frame: world_frame
tcp_frame: kinect2_move_frame
Expand Down
2 changes: 2 additions & 0 deletions godel_simple_gui/src/options/robot_scan_configuration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ void godel_simple_gui::RobotScanConfigWidget::update_display_fields()
ui_->LineEditWorldFrame->setText(QString::fromStdString(params_.world_frame));
ui_->LineEditTcpFrame->setText(QString::fromStdString(params_.tcp_frame));
ui_->LineEditGroupName->setText(QString::fromStdString(params_.group_name));
ui_->LineEditMoveScanVelScaling->setText(QString::number(params_.move_scan_vel_scaling));
ui_->CheckBoxStopOnPlanningError->setChecked(params_.stop_on_planning_error);

world_to_obj_pose_widget_->set_values(params_.world_to_obj_pose);
Expand All @@ -60,6 +61,7 @@ void godel_simple_gui::RobotScanConfigWidget::update_internal_fields()
params_.world_frame = ui_->LineEditWorldFrame->text().toStdString();
params_.tcp_frame = ui_->LineEditTcpFrame->text().toStdString();
params_.group_name = ui_->LineEditGroupName->text().toStdString();
params_.move_scan_vel_scaling = ui_->LineEditMoveScanVelScaling->text().toDouble();
params_.stop_on_planning_error = ui_->CheckBoxStopOnPlanningError->isChecked();

tf::poseTFToMsg(world_to_obj_pose_widget_->get_values(), params_.world_to_obj_pose);
Expand Down
31 changes: 27 additions & 4 deletions godel_simple_gui/src/uis/robot_scan_configuration.ui
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>540</width>
<height>563</height>
<height>583</height>
</rect>
</property>
<property name="font">
Expand Down Expand Up @@ -105,7 +105,7 @@
<x>30</x>
<y>40</y>
<width>281</width>
<height>441</height>
<height>461</height>
</rect>
</property>
<property name="frameShape">
Expand Down Expand Up @@ -299,13 +299,36 @@
</widget>
</item>
<item row="12" column="0">
<widget class="QLabel" name="moveScanVelScalingLabel">
<property name="text">
<string>Move Scan Vel Scaling</string>
</property>
</widget>
</item>
<item row="12" column="1">
<widget class="QLineEdit" name="LineEditMoveScanVelScaling">
<property name="inputMethodHints">
<set>Qt::ImhDigitsOnly</set>
</property>
<property name="inputMask">
<string/>
</property>
<property name="text">
<string/>
</property>
<property name="maxLength">
<number>8</number>
</property>
</widget>
</item>
<item row="13" column="0">
<widget class="QLabel" name="stopOnPlanningErrorLabel">
<property name="text">
<string>Stop On Plan Error</string>
</property>
</widget>
</item>
<item row="12" column="1">
<item row="13" column="1">
<widget class="QCheckBox" name="CheckBoxStopOnPlanningError"/>
</item>
</layout>
Expand Down Expand Up @@ -341,7 +364,7 @@
<property name="geometry">
<rect>
<x>33</x>
<y>500</y>
<y>520</y>
<width>491</width>
<height>33</height>
</rect>
Expand Down
4 changes: 4 additions & 0 deletions godel_surface_detection/src/scan/robot_scan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ RobotScan::RobotScan()
{

params_.group_name = "manipulator_asus";
params_.move_scan_vel_scaling = 1;
params_.home_position = "home";
params_.world_frame = "world_frame";
params_.tcp_frame = "kinect2_move_frame";
Expand All @@ -75,6 +76,7 @@ RobotScan::RobotScan()
bool RobotScan::init()
{
move_group_ptr_ = MoveGroupPtr(new moveit::planning_interface::MoveGroupInterface(params_.group_name));
move_group_ptr_->setMaxVelocityScalingFactor(params_.move_scan_vel_scaling);
move_group_ptr_->setEndEffectorLink(params_.tcp_frame);
move_group_ptr_->setPoseReferenceFrame(params_.world_frame);
move_group_ptr_->setPlanningTime(PLANNING_TIME);
Expand All @@ -97,6 +99,7 @@ bool RobotScan::load_parameters(const std::string& filename)
// otherwise load from parameters
ros::NodeHandle nh("~/robot_scan");
return loadParam(nh, "group_name", params_.group_name) &&
loadParam(nh, "move_scan_vel_scaling", params_.move_scan_vel_scaling) &&
loadParam(nh, "home_position", params_.home_position) &&
loadParam(nh, "world_frame", params_.world_frame) &&
loadParam(nh, "tcp_frame", params_.tcp_frame) &&
Expand Down Expand Up @@ -361,6 +364,7 @@ bool RobotScan::create_scan_trajectory(std::vector<geometry_msgs::Pose>& scan_po
scan_poses.push_back(pose);
}

move_group_ptr_->setMaxVelocityScalingFactor(params_.move_scan_vel_scaling);
move_group_ptr_->setEndEffectorLink(params_.tcp_frame);

return true;
Expand Down