Skip to content

Commit

Permalink
fixing format error
Browse files Browse the repository at this point in the history
  • Loading branch information
brettpac committed Jul 23, 2024
1 parent 6f481a0 commit b634d1f
Show file tree
Hide file tree
Showing 15 changed files with 272 additions and 266 deletions.
Empty file modified .clang-format
100644 → 100755
Empty file.
4 changes: 2 additions & 2 deletions .github/workflows/ci-ros-lint.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ on:
jobs:
ament_lint:
name: ament_${{ matrix.linter }}
runs-on: ubuntu-20.04
runs-on: ubuntu-latest
strategy:
fail-fast: false
matrix:
Expand All @@ -15,7 +15,7 @@ jobs:
- uses: ros-tooling/[email protected]
- uses: ros-tooling/[email protected]
with:
distribution: galactic
distribution: humble
linter: ${{ matrix.linter }}
package-name:
smacc2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,11 +85,11 @@ add_library(${PROJECT_NAME} SHARED
src/${PROJECT_NAME}/components/amcl/cp_amcl.cpp
src/${PROJECT_NAME}/components/slam_toolbox/cp_slam_toolbox.cpp

src/${PROJECT_NAME}/client_behaviors/cb_active_stop.cpp
src/${PROJECT_NAME}/client_behaviors/cb_load_waypoints_file.cpp
src/${PROJECT_NAME}/client_behaviors/cb_navigate_next_waypoint_free.cpp
src/${PROJECT_NAME}/client_behaviors/cb_active_stop.cpp
src/${PROJECT_NAME}/client_behaviors/cb_load_waypoints_file.cpp
src/${PROJECT_NAME}/client_behaviors/cb_navigate_next_waypoint_free.cpp
src/${PROJECT_NAME}/client_behaviors/cb_position_control_free_space.cpp
src/${PROJECT_NAME}/client_behaviors/cb_pure_spinning.cpp
src/${PROJECT_NAME}/client_behaviors/cb_pure_spinning.cpp
src/${PROJECT_NAME}/client_behaviors/cb_save_slam_map.cpp
)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,10 @@
#include <geometry_msgs/msg/twist.hpp>
#include <smacc2/smacc_asynchronous_client_behavior.hpp>

namespace cl_nav2z {
struct CbActiveStop : public smacc2::SmaccAsyncClientBehavior {
namespace cl_nav2z
{
struct CbActiveStop : public smacc2::SmaccAsyncClientBehavior
{
private:
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub_;

Expand All @@ -35,4 +37,4 @@ struct CbActiveStop : public smacc2::SmaccAsyncClientBehavior {

void onExit() override;
};
} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,12 @@
#include <nav2z_client/components/waypoints_navigator/cp_waypoints_navigator_base.hpp>
#include <smacc2/smacc_client_behavior.hpp>

namespace cl_nav2z {
struct CbLoadWaypointsFile : public smacc2::SmaccAsyncClientBehavior {
namespace cl_nav2z
{
struct CbLoadWaypointsFile : public smacc2::SmaccAsyncClientBehavior
{
public:
CbLoadWaypointsFile(std::string filepath) ;
CbLoadWaypointsFile(std::string filepath);

CbLoadWaypointsFile(std::string parameter_name, std::string packagenamesapce);

Expand All @@ -39,6 +41,6 @@ struct CbLoadWaypointsFile : public smacc2::SmaccAsyncClientBehavior {
std::optional<std::string> parameterName_;
std::optional<std::string> packageNamespace_;

cl_nav2z::CpWaypointNavigatorBase *waypointsNavigator_;
cl_nav2z::CpWaypointNavigatorBase * waypointsNavigator_;
};
} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,14 @@
*
******************************************************************************************************************/
#pragma once
#include <nav2z_client/components/waypoints_navigator/cp_waypoints_navigator_base.hpp>
#include <nav2z_client/client_behaviors/cb_position_control_free_space.hpp>
#include <nav2z_client/components/waypoints_navigator/cp_waypoints_navigator_base.hpp>

namespace cl_nav2z {
namespace cl_nav2z
{

class CbNavigateNextWaypointFree
: public cl_nav2z::CbPositionControlFreeSpace {
class CbNavigateNextWaypointFree : public cl_nav2z::CbPositionControlFreeSpace
{
public:
CbNavigateNextWaypointFree();

Expand All @@ -37,7 +38,7 @@ class CbNavigateNextWaypointFree
void onExit() override;

protected:
cl_nav2z::CpWaypointNavigatorBase *waypointsNavigator_;
cl_nav2z::CpWaypointNavigatorBase * waypointsNavigator_;
};

} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,10 @@
#include <nav2z_client/components/pose/cp_pose.hpp>
#include <smacc2/smacc_asynchronous_client_behavior.hpp>

namespace cl_nav2z {
struct CbPositionControlFreeSpace : public smacc2::SmaccAsyncClientBehavior {
namespace cl_nav2z
{
struct CbPositionControlFreeSpace : public smacc2::SmaccAsyncClientBehavior
{
private:
double targetYaw_;
bool goalReached_;
Expand All @@ -39,9 +41,8 @@ struct CbPositionControlFreeSpace : public smacc2::SmaccAsyncClientBehavior {

// Limit the maximum linear velocity and angular velocity to avoid sudden
// movements
double max_linear_velocity = 1.0; // Adjust this value according to your needs
double max_angular_velocity =
1.0; // Adjust this value according to your needs
double max_linear_velocity = 1.0; // Adjust this value according to your needs
double max_angular_velocity = 1.0; // Adjust this value according to your needs

rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub_;

Expand All @@ -60,4 +61,4 @@ struct CbPositionControlFreeSpace : public smacc2::SmaccAsyncClientBehavior {

void onExit() override;
};
} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,10 @@
#include <geometry_msgs/msg/twist.hpp>
#include <smacc2/smacc_asynchronous_client_behavior.hpp>

namespace cl_nav2z {
struct CbPureSpinning : public smacc2::SmaccAsyncClientBehavior {
namespace cl_nav2z
{
struct CbPureSpinning : public smacc2::SmaccAsyncClientBehavior
{
private:
double targetYaw__rads;
bool goalReached_;
Expand All @@ -43,4 +45,4 @@ struct CbPureSpinning : public smacc2::SmaccAsyncClientBehavior {

void onExit() override;
};
} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -23,25 +23,24 @@
#include <memory>
#include <nav2_msgs/srv/save_map.hpp>
#include <slam_toolbox/srv/save_map.hpp>
#include <slam_toolbox/srv/save_map.hpp>
#include <smacc2/client_behaviors/cb_call_service.hpp>
#include <smacc2/smacc_asynchronous_client_behavior.hpp>


namespace cl_nav2z {
namespace cl_nav2z
{
using namespace std::chrono_literals;
template <typename TService>
using CbServiceCall = smacc2::client_behaviors::CbServiceCall<TService>;


struct CbSaveSlamMap : public CbServiceCall<nav2_msgs::srv::SaveMap> {

public:
struct CbSaveSlamMap : public CbServiceCall<nav2_msgs::srv::SaveMap>
{
public:
CbSaveSlamMap();
// void onEntry() override {}

void onExit() override;

std::shared_ptr<nav2_msgs::srv::SaveMap::Request> getRequest(/*slam_toolbox::srv::SaveMap_Request_<std::allocator<void> >::_name_type saved_map_name*/) ;
std::shared_ptr<nav2_msgs::srv::SaveMap::Request> getRequest(
/*slam_toolbox::srv::SaveMap_Request_<std::allocator<void> >::_name_type saved_map_name*/);
};
} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -24,29 +24,30 @@

#include <nav2z_client/client_behaviors/cb_active_stop.hpp>

namespace cl_nav2z {
namespace cl_nav2z
{
CbActiveStop::CbActiveStop() {}

void CbActiveStop::onEntry() {
void CbActiveStop::onEntry()
{
auto nh = this->getNode();
cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>(
"/cmd_vel", rclcpp::QoS(1));
cmd_vel_pub_ = nh->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", rclcpp::QoS(1));

rclcpp::Rate loop_rate(5);
geometry_msgs::msg::Twist cmd_vel_msg;
while (!this->isShutdownRequested()) {
while (!this->isShutdownRequested())
{
cmd_vel_msg.linear.x = 0;
cmd_vel_msg.angular.z = 0;

cmd_vel_pub_->publish(cmd_vel_msg);
loop_rate.sleep();
}
RCLCPP_INFO_STREAM(getLogger(),
"[" << getName() << "] Finished behavior execution");
RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] Finished behavior execution");

this->postSuccessEvent();
}

void CbActiveStop::onExit() {}

} // namespace cl_nav2z
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -18,34 +18,40 @@
*
******************************************************************************************************************/

#include <smacc2/smacc_client_behavior.hpp>
#include <nav2z_client/client_behaviors/cb_load_waypoints_file.hpp>
#include <nav2z_client/components/waypoints_navigator/cp_waypoints_navigator_base.hpp>
#include <nav2z_client/client_behaviors/cb_load_waypoints_file.hpp>

namespace cl_nav2z {
#include <smacc2/smacc_client_behavior.hpp>

CbLoadWaypointsFile::CbLoadWaypointsFile(std::string filepath) : filepath_(filepath) {}
namespace cl_nav2z
{

CbLoadWaypointsFile::CbLoadWaypointsFile(std::string parameter_name, std::string packagenamesapce)
: parameterName_(parameter_name), packageNamespace_(packagenamesapce) {}
CbLoadWaypointsFile::CbLoadWaypointsFile(std::string filepath) : filepath_(filepath) {}

void CbLoadWaypointsFile::onEntry() {
requiresComponent(waypointsNavigator_); // this is a component from the
// nav2z_client library
CbLoadWaypointsFile::CbLoadWaypointsFile(std::string parameter_name, std::string packagenamesapce)
: parameterName_(parameter_name), packageNamespace_(packagenamesapce)
{
}

if (filepath_) {
this->waypointsNavigator_->loadWayPointsFromFile(filepath_.value());
} else {
RCLCPP_INFO(getLogger(), "Loading waypoints from parameter %s",
parameterName_.value().c_str());
this->waypointsNavigator_->loadWaypointsFromYamlParameter(
parameterName_.value(), packageNamespace_.value());
}
void CbLoadWaypointsFile::onEntry()
{
requiresComponent(waypointsNavigator_); // this is a component from the
// nav2z_client library

// change this to skip some points of the yaml file, default = 0
waypointsNavigator_->currentWaypoint_ = 0;
this->postSuccessEvent();
if (filepath_)
{
this->waypointsNavigator_->loadWayPointsFromFile(filepath_.value());
}
else
{
RCLCPP_INFO(getLogger(), "Loading waypoints from parameter %s", parameterName_.value().c_str());
this->waypointsNavigator_->loadWaypointsFromYamlParameter(
parameterName_.value(), packageNamespace_.value());
}

// change this to skip some points of the yaml file, default = 0
waypointsNavigator_->currentWaypoint_ = 0;
this->postSuccessEvent();
}

void CbLoadWaypointsFile::onExit() {}
} // namespace cl_nav2z
void CbLoadWaypointsFile::onExit() {}
} // namespace cl_nav2z
Original file line number Diff line number Diff line change
Expand Up @@ -19,40 +19,36 @@
******************************************************************************************************************/
#include <nav2z_client/client_behaviors/cb_navigate_next_waypoint_free.hpp>


namespace cl_nav2z {

CbNavigateNextWaypointFree::CbNavigateNextWaypointFree() {}

CbNavigateNextWaypointFree::~CbNavigateNextWaypointFree() {}

void CbNavigateNextWaypointFree::onEntry() {
requiresComponent(this->waypointsNavigator_);
this->target_pose_ = this->waypointsNavigator_->getCurrentPose();

this->onSuccess(&CbNavigateNextWaypointFree::CbNavigateNextWaypointFree::onSucessCallback, this);
RCLCPP_INFO_STREAM(
getLogger(),
"[CbNavigateNextWaypoint] initial load file target pose: x: "
<< this->target_pose_.position.x
<< ", y: " << this->target_pose_.position.y);
CbPositionControlFreeSpace::onEntry();
}

void CbNavigateNextWaypointFree::onSucessCallback() {
RCLCPP_INFO_STREAM(
getLogger(),
"[CbNavigateNextWaypoint] Success on planning to next waypoint");
this->waypointsNavigator_->notifyGoalReached();
this->waypointsNavigator_->forward(1);
RCLCPP_INFO_STREAM(
getLogger(), "[CbNavigateNextWaypoint] next position index: "
<< this->waypointsNavigator_->getCurrentWaypointIndex()
<< "/"
<< this->waypointsNavigator_->getWaypoints().size());
}

void CbNavigateNextWaypointFree::onExit() {}


} // namespace cl_nav2z
namespace cl_nav2z
{

CbNavigateNextWaypointFree::CbNavigateNextWaypointFree() {}

CbNavigateNextWaypointFree::~CbNavigateNextWaypointFree() {}

void CbNavigateNextWaypointFree::onEntry()
{
requiresComponent(this->waypointsNavigator_);
this->target_pose_ = this->waypointsNavigator_->getCurrentPose();

this->onSuccess(&CbNavigateNextWaypointFree::CbNavigateNextWaypointFree::onSucessCallback, this);
RCLCPP_INFO_STREAM(
getLogger(), "[CbNavigateNextWaypoint] initial load file target pose: x: "
<< this->target_pose_.position.x << ", y: " << this->target_pose_.position.y);
CbPositionControlFreeSpace::onEntry();
}

void CbNavigateNextWaypointFree::onSucessCallback()
{
RCLCPP_INFO_STREAM(getLogger(), "[CbNavigateNextWaypoint] Success on planning to next waypoint");
this->waypointsNavigator_->notifyGoalReached();
this->waypointsNavigator_->forward(1);
RCLCPP_INFO_STREAM(
getLogger(), "[CbNavigateNextWaypoint] next position index: "
<< this->waypointsNavigator_->getCurrentWaypointIndex() << "/"
<< this->waypointsNavigator_->getWaypoints().size());
}

void CbNavigateNextWaypointFree::onExit() {}

} // namespace cl_nav2z
Loading

0 comments on commit b634d1f

Please sign in to comment.