Skip to content

Commit

Permalink
perception used calss instead of struct
Browse files Browse the repository at this point in the history
  • Loading branch information
mayman99 committed Jul 19, 2018
1 parent 74dc5ff commit af46fee
Show file tree
Hide file tree
Showing 4 changed files with 88 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -78,16 +78,6 @@ struct GroupMetaData
std::string default_planner_; // Name of the default planner to use
};

/**
* Reusable parameter struct which may be used in reading and writing configuration files
*/
struct GenericParameter
{
std::string name; // name of parameter
std::string value; // value parameter will receive (but as a string)
std::string comment; // comment briefly describing what this parameter does
};

/**
* ROS Controllers settings which may be set in the config files
*/
Expand All @@ -98,6 +88,16 @@ struct ROSControlConfig
std::vector<std::string> joints_; // joints controller by this controller
};

/**
* Planning parameters which may be set in the config files
*/
struct OmplPlanningParameter
{
std::string name; // name of parameter
std::string value; // value parameter will receive (but as a string)
std::string comment; // comment briefly describing what this parameter does
};

/** \brief This class describes the OMPL planners by name, type, and parameter list, used to create the
* ompl_planning.yaml file */
class OMPLPlannerDescription
Expand All @@ -122,19 +122,61 @@ class OMPLPlannerDescription
* @parameter: value: value of parameter as a string
* @parameter: value: value of parameter as a string
*/
void addGenericParameter(const std::string& name, const std::string& value = "", const std::string& comment = "")
void addParameter(const std::string& name, const std::string& value = "", const std::string& comment = "")
{
GenericParameter temp;
OmplPlanningParameter temp;
temp.name = name;
temp.value = value;
temp.comment = comment;
parameter_list_.push_back(temp);
}
std::vector<GenericParameter> parameter_list_;
std::vector<OmplPlanningParameter> parameter_list_;
std::string name_; // name of planner
std::string type_; // type of planner (geometric)
};

/**
* Reusable parameter class which may be used in reading and writing configuration files
*/
class GenericParameter
{
public:
GenericParameter()
{
comment_ = "";
};

void setName(std::string name)
{
name_ = name;
};
void setValue(std::string value)
{
value_ = value;
};
void setComment(std::string comment)
{
comment_ = comment;
};
std::string getName()
{
return name_;
};
std::string getValue()
{
return value_;
};
std::string getComment()
{
return comment_;
};

private:
std::string name_; // name of parameter
std::string value_; // value parameter will receive (but as a string)
std::string comment_; // comment briefly describing what this parameter does
};

MOVEIT_CLASS_FORWARD(MoveItConfigData);

/** \brief This class is shared with all widgets and contains the common configuration data
Expand Down
19 changes: 11 additions & 8 deletions moveit_setup_assistant/src/tools/moveit_config_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -864,7 +864,7 @@ bool MoveItConfigData::output3DSensorPluginYAML(const std::string& file_path)
for (auto& parameter : sensors_plugin_config_parameter_list_[0])
{
emitter << YAML::Key << parameter.first;
emitter << YAML::Value << parameter.second.value;
emitter << YAML::Value << parameter.second.getValue();
}
}

Expand Down Expand Up @@ -1474,11 +1474,11 @@ bool MoveItConfigData::input3DSensorsYAML(const std::string& default_file_path,
{
for (YAML::const_iterator sensor_it = sensor_node.begin(); sensor_it != sensor_node.end(); ++sensor_it)
{
sensor_param.name = sensor_it->first.as<std::string>();
sensor_param.value = sensor_it->second.as<std::string>();
sensor_param.setName(sensor_it->first.as<std::string>());
sensor_param.setValue(sensor_it->second.as<std::string>());

// Set the key as the parameter name to make accessing it easier
sensor_map[sensor_param.name] = sensor_param;
sensor_map[sensor_it->first.as<std::string>()] = sensor_param;
}
sensors_plugin_config_parameter_list_.push_back(sensor_map);
}
Expand Down Expand Up @@ -1526,11 +1526,11 @@ bool MoveItConfigData::input3DSensorsYAML(const std::string& default_file_path,
{
for (YAML::const_iterator sensor_it = sensor_node.begin(); sensor_it != sensor_node.end(); ++sensor_it)
{
sensor_param.name = sensor_it->first.as<std::string>();
sensor_param.value = sensor_it->second.as<std::string>();
sensor_param.setName(sensor_it->first.as<std::string>());
sensor_param.setValue(sensor_it->second.as<std::string>());

// Set the key as the parameter name to make accessing it easier
sensor_map[sensor_param.name] = sensor_param;
sensor_map[sensor_it->first.as<std::string>()] = sensor_param;
}
sensors_plugin_config_parameter_list_.push_back(sensor_map);
}
Expand Down Expand Up @@ -1633,7 +1633,10 @@ void MoveItConfigData::addGenericParameterToSensorPluginConfig(const std::string
const std::string& comment)
{
// Use index 0 since we only write one plugin
sensors_plugin_config_parameter_list_[0][name] = {.name = name, .value = value, .comment = comment };
GenericParameter new_parameter;
new_parameter.setName(name);
new_parameter.setValue(value);
sensors_plugin_config_parameter_list_[0][name] = new_parameter;
}

// ******************************************************************************************
Expand Down
38 changes: 20 additions & 18 deletions moveit_setup_assistant/src/widgets/perception_widget.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -308,29 +308,31 @@ void PerceptionWidget::loadSensorPluginsComboBox()
std::vector<std::map<std::string, GenericParameter> > sensors_vec_map = config_data_->getSensorPluginConfig();
for (std::size_t i = 0; i < sensors_vec_map.size(); ++i)
{
if (sensors_vec_map[i]["sensor_plugin"].value == std::string("occupancy_map_monitor/PointCloudOctomapUpdater"))
if (sensors_vec_map[i]["sensor_plugin"].getValue() == std::string("occupancy_map_monitor/PointCloudOctomapUpdater"))
{
sensor_plugin_field_->setCurrentIndex(1);
point_cloud_topic_field_->setText(QString(sensors_vec_map[i]["point_cloud_topic"].value.c_str()));
max_range_field_->setText(QString(sensors_vec_map[i]["max_range"].value.c_str()));
point_subsample_field_->setText(QString(sensors_vec_map[i]["point_subsample"].value.c_str()));
padding_offset_field_->setText(QString(sensors_vec_map[i]["padding_offset"].value.c_str()));
padding_scale_field_->setText(QString(sensors_vec_map[i]["padding_scale"].value.c_str()));
max_update_rate_field_->setText(QString(sensors_vec_map[i]["max_update_rate"].value.c_str()));
filtered_cloud_topic_field_->setText(QString(sensors_vec_map[i]["filtered_cloud_topic"].value.c_str()));
point_cloud_topic_field_->setText(QString(sensors_vec_map[i]["point_cloud_topic"].getValue().c_str()));
max_range_field_->setText(QString(sensors_vec_map[i]["max_range"].getValue().c_str()));
point_subsample_field_->setText(QString(sensors_vec_map[i]["point_subsample"].getValue().c_str()));
padding_offset_field_->setText(QString(sensors_vec_map[i]["padding_offset"].getValue().c_str()));
padding_scale_field_->setText(QString(sensors_vec_map[i]["padding_scale"].getValue().c_str()));
max_update_rate_field_->setText(QString(sensors_vec_map[i]["max_update_rate"].getValue().c_str()));
filtered_cloud_topic_field_->setText(QString(sensors_vec_map[i]["filtered_cloud_topic"].getValue().c_str()));
}
else if (sensors_vec_map[i]["sensor_plugin"].value == std::string("occupancy_map_monitor/DepthImageOctomapUpdater"))
else if (sensors_vec_map[i]["sensor_plugin"].getValue() ==
std::string("occupancy_map_monitor/DepthImageOctomapUpdater"))
{
sensor_plugin_field_->setCurrentIndex(2);
image_topic_field_->setText(QString(sensors_vec_map[i]["image_topic"].value.c_str()));
queue_size_field_->setText(QString(sensors_vec_map[i]["queue_size"].value.c_str()));
near_clipping_field_->setText(QString(sensors_vec_map[i]["near_clipping_plane_distance"].value.c_str()));
far_clipping_field_->setText(QString(sensors_vec_map[i]["far_clipping_plane_distance"].value.c_str()));
shadow_threshold_field_->setText(QString(sensors_vec_map[i]["shadow_threshold"].value.c_str()));
depth_padding_scale_field_->setText(QString(sensors_vec_map[i]["padding_scale"].value.c_str()));
depth_padding_offset_field_->setText(QString(sensors_vec_map[i]["padding_offset"].value.c_str()));
depth_filtered_cloud_topic_field_->setText(QString(sensors_vec_map[i]["filtered_cloud_topic"].value.c_str()));
depth_max_update_rate_field_->setText(QString(sensors_vec_map[i]["max_update_rate"].value.c_str()));
image_topic_field_->setText(QString(sensors_vec_map[i]["image_topic"].getValue().c_str()));
queue_size_field_->setText(QString(sensors_vec_map[i]["queue_size"].getValue().c_str()));
near_clipping_field_->setText(QString(sensors_vec_map[i]["near_clipping_plane_distance"].getValue().c_str()));
far_clipping_field_->setText(QString(sensors_vec_map[i]["far_clipping_plane_distance"].getValue().c_str()));
shadow_threshold_field_->setText(QString(sensors_vec_map[i]["shadow_threshold"].getValue().c_str()));
depth_padding_scale_field_->setText(QString(sensors_vec_map[i]["padding_scale"].getValue().c_str()));
depth_padding_offset_field_->setText(QString(sensors_vec_map[i]["padding_offset"].getValue().c_str()));
depth_filtered_cloud_topic_field_->setText(
QString(sensors_vec_map[i]["filtered_cloud_topic"].getValue().c_str()));
depth_max_update_rate_field_->setText(QString(sensors_vec_map[i]["max_update_rate"].getValue().c_str()));
}
}

Expand Down
4 changes: 2 additions & 2 deletions moveit_setup_assistant/test/moveit_config_data_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,10 +138,10 @@ TEST_F(MoveItConfigData, ReadingSensorsConfig)
// Make sure both are parsed correctly
EXPECT_EQ(config_data_->getSensorPluginConfig().size(), 2);

EXPECT_EQ(config_data_->getSensorPluginConfig()[0]["sensor_plugin"].value,
EXPECT_EQ(config_data_->getSensorPluginConfig()[0]["sensor_plugin"].getValue(),
std::string("occupancy_map_monitor/PointCloudOctomapUpdater"));

EXPECT_EQ(config_data_->getSensorPluginConfig()[1]["sensor_plugin"].value,
EXPECT_EQ(config_data_->getSensorPluginConfig()[1]["sensor_plugin"].getValue(),
std::string("occupancy_map_monitor/DepthImageOctomapUpdater"));
}

Expand Down

0 comments on commit af46fee

Please sign in to comment.