45 const MoveBaseFlexConfig& config)
46 : AbstractControllerExecution(name, controller_ptr, vel_pub, goal_pub, tf_listener_ptr, toAbstract(config))
61 mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
62 abstract_config.controller_frequency = config.controller_frequency;
63 abstract_config.controller_patience = config.controller_patience;
64 abstract_config.controller_max_retries = config.controller_max_retries;
65 abstract_config.oscillation_timeout = config.oscillation_timeout;
66 abstract_config.oscillation_distance = config.oscillation_distance;
67 return abstract_config;
71 const geometry_msgs::TwistStamped& robot_velocity,
72 geometry_msgs::TwistStamped& vel_cmd, std::string& message)
83 return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);