diff --git a/cfg/fiss_planner.cfg b/cfg/fiss_planner.cfg index 9d88b8a..c37ca69 100755 --- a/cfg/fiss_planner.cfg +++ b/cfg/fiss_planner.cfg @@ -55,4 +55,4 @@ gen.add("track_error_gain", double_t, 1, "Default: 1.0", 1.0, 0, 1.0) gen.add("traj_max_size", int_t, 0, "Default: 10", 10, 5, 30) gen.add("traj_min_size", int_t, 0, "Default: 5", 5, 5, 20) -exit(gen.generate(PACKAGE, "fiss_planner", "fiss_planner_")) +exit(gen.generate(PACKAGE, "fiss_planner", "fiss_planner")) diff --git a/include/fiss_planner/fiss_planner_node.h b/include/fiss_planner/fiss_planner_node.h index 6f2546d..b9ca6c0 100644 --- a/include/fiss_planner/fiss_planner_node.h +++ b/include/fiss_planner/fiss_planner_node.h @@ -30,7 +30,7 @@ #include #include -#include +#include #include "fiss_planner/pid.hpp" #include "fiss_planner/visualization.hpp" @@ -103,8 +103,8 @@ class FissPlannerNode ros::NodeHandle nh; tf2_ros::Buffer tf_buffer; tf2_ros::TransformListener tf_listener; - dynamic_reconfigure::Server server; - dynamic_reconfigure::Server::CallbackType f; + dynamic_reconfigure::Server server; + dynamic_reconfigure::Server::CallbackType f; // ###################################### Private Functions ###################################### diff --git a/src/fiss_planner_node.cpp b/src/fiss_planner_node.cpp index 2cf68d6..408137a 100755 --- a/src/fiss_planner_node.cpp +++ b/src/fiss_planner_node.cpp @@ -46,7 +46,7 @@ bool USE_HEURISTIC; bool SETTINGS_UPDATED = false; // Dynamic parameter server callback function -void dynamicParamCallback(fiss_planner::fiss_planner_Config& config, uint32_t level) +void dynamicParamCallback(fiss_planner::fiss_plannerConfig& config, uint32_t level) { // General Settings CHECK_COLLISION = config.check_collision;