Compare commits
4 Commits
eb52edc6e8
...
3d621de809
| Author | SHA1 | Date | |
|---|---|---|---|
| 3d621de809 | |||
| 1f9e9f1398 | |||
| 9208c8bcdc | |||
| 6c6e5b44f8 |
@@ -332,21 +332,19 @@ void Costmap2DROBOT::copyParentParameters(const std::string& costmap_name,
|
|||||||
const std::string& plugin_type,
|
const std::string& plugin_type,
|
||||||
robot::NodeHandle& nh)
|
robot::NodeHandle& nh)
|
||||||
{
|
{
|
||||||
robot::NodeHandle priv_nh_1(nh, costmap_name);
|
robot::NodeHandle costmap_nh(nh, costmap_name);
|
||||||
robot::NodeHandle target_layer(priv_nh_1, plugin_name);
|
robot::NodeHandle costmap_plugin_nh(costmap_nh, plugin_name);
|
||||||
robot::NodeHandle priv_nh_2(nh, plugin_name);
|
robot::NodeHandle plugin_nh(nh, plugin_name);
|
||||||
// robot::log_error("TEST: %s",priv_nh_2.getNamespace().c_str());
|
|
||||||
|
|
||||||
if(plugin_type == "StaticLayer")
|
if(plugin_type == "StaticLayer")
|
||||||
{
|
{
|
||||||
std::string map_topic;
|
std::string map_topic;
|
||||||
int unknown_cost_value;
|
int unknown_cost_value;
|
||||||
int lethal_cost_threshold;
|
int lethal_cost_threshold;
|
||||||
bool track_unknown_space;
|
bool track_unknown_space;
|
||||||
move_parameter(priv_nh_2, target_layer, "map_topic", map_topic);
|
move_parameter(plugin_nh, costmap_plugin_nh, "map_topic", map_topic);
|
||||||
move_parameter(priv_nh_2, target_layer, "unknown_cost_value", unknown_cost_value);
|
move_parameter(plugin_nh, costmap_plugin_nh, "unknown_cost_value", unknown_cost_value);
|
||||||
move_parameter(priv_nh_2, target_layer, "lethal_cost_threshold", lethal_cost_threshold);
|
move_parameter(plugin_nh, costmap_plugin_nh, "lethal_cost_threshold", lethal_cost_threshold);
|
||||||
move_parameter(priv_nh_2, target_layer, "track_unknown_space", track_unknown_space);
|
move_parameter(plugin_nh, costmap_plugin_nh, "track_unknown_space", track_unknown_space);
|
||||||
}
|
}
|
||||||
else if(plugin_type == "VoxelLayer")
|
else if(plugin_type == "VoxelLayer")
|
||||||
{
|
{
|
||||||
@@ -356,24 +354,23 @@ void Costmap2DROBOT::copyParentParameters(const std::string& costmap_name,
|
|||||||
int mark_threshold;
|
int mark_threshold;
|
||||||
int unknown_threshold;
|
int unknown_threshold;
|
||||||
bool publish_voxel_map;
|
bool publish_voxel_map;
|
||||||
move_parameter(priv_nh_2, target_layer, "origin_z", origin_z);
|
move_parameter(plugin_nh, costmap_plugin_nh, "origin_z", origin_z);
|
||||||
move_parameter(priv_nh_2, target_layer, "z_resolution", z_resolution);
|
move_parameter(plugin_nh, costmap_plugin_nh, "z_resolution", z_resolution);
|
||||||
move_parameter(priv_nh_2, target_layer, "z_voxels", z_voxels);
|
move_parameter(plugin_nh, costmap_plugin_nh, "z_voxels", z_voxels);
|
||||||
move_parameter(priv_nh_2, target_layer, "mark_threshold", mark_threshold);
|
move_parameter(plugin_nh, costmap_plugin_nh, "mark_threshold", mark_threshold);
|
||||||
move_parameter(priv_nh_2, target_layer, "unknown_threshold", unknown_threshold);
|
move_parameter(plugin_nh, costmap_plugin_nh, "unknown_threshold", unknown_threshold);
|
||||||
move_parameter(priv_nh_2, target_layer, "publish_voxel_map", publish_voxel_map);
|
move_parameter(plugin_nh, costmap_plugin_nh, "publish_voxel_map", publish_voxel_map);
|
||||||
if(priv_nh_2.hasParam("observation_sources"))
|
if(plugin_nh.hasParam("observation_sources"))
|
||||||
{
|
{
|
||||||
std::string topics_string;
|
std::string topics_string;
|
||||||
move_parameter(priv_nh_2, target_layer, "observation_sources", topics_string);
|
move_parameter(plugin_nh, costmap_plugin_nh, "observation_sources", topics_string);
|
||||||
robot::log_error("topics_string: %s", topics_string.c_str());
|
robot::log_error("topics_string: %s", topics_string.c_str());
|
||||||
std::stringstream ss(topics_string);
|
std::stringstream ss(topics_string);
|
||||||
std::string source;
|
std::string source;
|
||||||
while (ss >> source)
|
while (ss >> source)
|
||||||
{
|
{
|
||||||
robot::NodeHandle priv_nh_3(priv_nh_2, source);
|
robot::NodeHandle plugin_nh_element(plugin_nh, source);
|
||||||
robot::NodeHandle target_layer_2(target_layer, source);
|
robot::NodeHandle costmap_plugin_nh_element(costmap_plugin_nh, source);
|
||||||
robot::log_warning("priv_nh_3: %s",priv_nh_3.getNamespace().c_str());
|
|
||||||
std::string topic;
|
std::string topic;
|
||||||
std::string data_type;
|
std::string data_type;
|
||||||
bool clearing;
|
bool clearing;
|
||||||
@@ -381,15 +378,14 @@ void Costmap2DROBOT::copyParentParameters(const std::string& costmap_name,
|
|||||||
bool inf_is_valid;
|
bool inf_is_valid;
|
||||||
double min_obstacle_height;
|
double min_obstacle_height;
|
||||||
double max_obstacle_height;
|
double max_obstacle_height;
|
||||||
move_parameter(priv_nh_2, target_layer_2, "topic", topic);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "topic", topic);
|
||||||
robot::log_error("topic: %s", topic.c_str());
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "data_type", data_type);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "data_type", data_type);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "clearing", clearing);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "clearing", clearing);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "marking", marking);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "marking", marking);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "inf_is_valid", inf_is_valid);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "inf_is_valid", inf_is_valid);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "min_obstacle_height", min_obstacle_height);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "min_obstacle_height", min_obstacle_height);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "max_obstacle_height", max_obstacle_height);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "max_obstacle_height", max_obstacle_height);
|
robot::log_info("topic: %s data_type: %s clearing: %d marking: %d inf_is_valid: %d min_obstacle_height: %f max_obstacle_height: %f", topic.c_str(), data_type.c_str(), clearing, marking, inf_is_valid, min_obstacle_height, max_obstacle_height);
|
||||||
target_layer_2.printParams();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -399,21 +395,21 @@ void Costmap2DROBOT::copyParentParameters(const std::string& costmap_name,
|
|||||||
double raytrace_range;
|
double raytrace_range;
|
||||||
double obstacle_range;
|
double obstacle_range;
|
||||||
bool track_unknown_space;
|
bool track_unknown_space;
|
||||||
move_parameter(priv_nh_2, target_layer, "max_obstacle_height", max_obstacle_height);
|
move_parameter(plugin_nh, costmap_plugin_nh, "max_obstacle_height", max_obstacle_height);
|
||||||
move_parameter(priv_nh_2, target_layer, "raytrace_range", raytrace_range);
|
move_parameter(plugin_nh, costmap_plugin_nh, "raytrace_range", raytrace_range);
|
||||||
move_parameter(priv_nh_2, target_layer, "obstacle_range", obstacle_range);
|
move_parameter(plugin_nh, costmap_plugin_nh, "obstacle_range", obstacle_range);
|
||||||
move_parameter(priv_nh_2, target_layer, "track_unknown_space", track_unknown_space);
|
move_parameter(plugin_nh, costmap_plugin_nh, "track_unknown_space", track_unknown_space);
|
||||||
if(priv_nh_2.hasParam("observation_sources"))
|
if(plugin_nh.hasParam("observation_sources"))
|
||||||
{
|
{
|
||||||
std::string topics_string;
|
std::string topics_string;
|
||||||
move_parameter(priv_nh_2, target_layer, "observation_sources", topics_string);
|
move_parameter(plugin_nh, costmap_plugin_nh, "observation_sources", topics_string);
|
||||||
robot::log_error("topics_string: %s", topics_string.c_str());
|
robot::log_error("topics_string: %s", topics_string.c_str());
|
||||||
std::stringstream ss(topics_string);
|
std::stringstream ss(topics_string);
|
||||||
std::string source;
|
std::string source;
|
||||||
while (ss >> source)
|
while (ss >> source)
|
||||||
{
|
{
|
||||||
robot::NodeHandle priv_nh_3(priv_nh_2, source);
|
robot::NodeHandle plugin_nh_element(plugin_nh, source);
|
||||||
robot::NodeHandle target_layer_2(target_layer, source);
|
robot::NodeHandle costmap_plugin_nh_element(costmap_plugin_nh, source);
|
||||||
std::string topic;
|
std::string topic;
|
||||||
std::string data_type;
|
std::string data_type;
|
||||||
bool clearing;
|
bool clearing;
|
||||||
@@ -421,23 +417,23 @@ void Costmap2DROBOT::copyParentParameters(const std::string& costmap_name,
|
|||||||
bool inf_is_valid;
|
bool inf_is_valid;
|
||||||
double min_obstacle_height;
|
double min_obstacle_height;
|
||||||
double max_obstacle_height;
|
double max_obstacle_height;
|
||||||
move_parameter(priv_nh_2, target_layer_2, "topic", topic);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "topic", topic);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "data_type", data_type);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "data_type", data_type);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "clearing", clearing);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "clearing", clearing);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "marking", marking);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "marking", marking);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "inf_is_valid", inf_is_valid);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "inf_is_valid", inf_is_valid);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "min_obstacle_height", min_obstacle_height);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "min_obstacle_height", min_obstacle_height);
|
||||||
move_parameter(priv_nh_2, target_layer_2, "max_obstacle_height", max_obstacle_height);
|
move_parameter(plugin_nh_element, costmap_plugin_nh_element, "max_obstacle_height", max_obstacle_height);
|
||||||
|
robot::log_info("topic: %s data_type: %s clearing: %d marking: %d inf_is_valid: %d min_obstacle_height: %f max_obstacle_height: %f", topic.c_str(), data_type.c_str(), clearing, marking, inf_is_valid, min_obstacle_height, max_obstacle_height);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
else if(plugin_type == "InflationLayer")
|
else if(plugin_type == "InflationLayer")
|
||||||
{
|
{
|
||||||
double cost_scaling_factor;
|
double cost_scaling_factor;
|
||||||
double inflation_radius;
|
double inflation_radius;
|
||||||
move_parameter(priv_nh_2, target_layer, "cost_scaling_factor", cost_scaling_factor);
|
move_parameter(plugin_nh, costmap_plugin_nh, "cost_scaling_factor", cost_scaling_factor);
|
||||||
move_parameter(priv_nh_2, target_layer, "inflation_radius", inflation_radius);
|
move_parameter(plugin_nh, costmap_plugin_nh, "inflation_radius", inflation_radius);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user