Skip to content

Commit

Permalink
build fix
Browse files Browse the repository at this point in the history
  • Loading branch information
ibrahimhroob committed Dec 7, 2024
1 parent eca83dc commit 853d94e
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class TeachRepeatController : public nav2_core::Controller
const geometry_msgs::msg::Twist & velocity,
nav2_core::GoalChecker * goal_checker) override;

void setPlan(const nav_msgs::msg::Path & path) override {};
void setPlan(const nav_msgs::msg::Path & path) override {(void) path;};

protected:

Expand All @@ -60,7 +60,7 @@ class TeachRepeatController : public nav2_core::Controller
std::queue<geometry_msgs::msg::TwistStamped> vel_queue_;
std::mutex queue_mutex_;

std::shared_ptr<rclcpp_lifecycle::LifecycleSubscriper<geometry_msgs::msg::TwistStamped>> cmd_vel_sub_;
rclcpp::Subscription<geometry_msgs::msg::TwistStamped>::SharedPtr cmd_vel_sub_;

void velCallback(const geometry_msgs::msg::TwistStamped::SharedPtr msg);
void clearQueue();
Expand Down
10 changes: 4 additions & 6 deletions src/teach_repeat_controller/src/teach_repeat_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@ void TeachRepeatController::configure(
logger_ = node->get_logger();
clock_ = node->get_clock();

declare_parameter_if_not_declared(
nav2_util::declare_parameter_if_not_declared(
node, plugin_name_ + ".desired_linear_vel", rclcpp::ParameterValue(
1.0));
declare_parameter_if_not_declared(
nav2_util::declare_parameter_if_not_declared(
node, plugin_name_ + ".max_angular_vel", rclcpp::ParameterValue(
1.0));
declare_parameter_if_not_declared(
nav2_util::declare_parameter_if_not_declared(
node, plugin_name_ + ".vel_cmd_topic_", rclcpp::ParameterValue(
"/teach_repeat/vel_cmd"));

Expand Down Expand Up @@ -64,15 +64,13 @@ void TeachRepeatController::activate() {
logger_,
"Activating controller: %s of type teach_repeat_controller::TeachRepeatController\" %s",
plugin_name_.c_str(),plugin_name_.c_str());
// global_pub_->on_activate();
}

void TeachRepeatController::deactivate() {
RCLCPP_INFO(
logger_,
"Dectivating controller: %s of type teach_repeat_controller::TeachRepeatController\" %s",
plugin_name_.c_str(),plugin_name_.c_str());
// global_pub_->on_deactivate();
}

void TeachRepeatController::setSpeedLimit(const double& speed_limit, const bool& percentage) {
Expand All @@ -82,7 +80,7 @@ void TeachRepeatController::setSpeedLimit(const double& speed_limit, const bool&

geometry_msgs::msg::TwistStamped TeachRepeatController::computeVelocityCommands(
const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::TwistStamped & velocity,
const geometry_msgs::msg::Twist & velocity,
nav2_core::GoalChecker * goal_checker) {
(void)velocity;
(void)goal_checker;
Expand Down

0 comments on commit 853d94e

Please sign in to comment.