Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion scout_base/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ find_package(nav_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)

find_package(scout_msgs REQUIRED)
find_package(ugv_sdk REQUIRED)
Expand All @@ -41,6 +42,7 @@ set(DEPENDENCIES
"std_msgs"
"tf2"
"tf2_ros"
"tf2_geometry_msgs"
"scout_msgs"
"sensor_msgs"
)
Expand All @@ -57,7 +59,7 @@ add_executable(scout_base_node
src/scout_base_ros.cpp
src/scout_base_node.cpp)
target_link_libraries(scout_base_node ugv_sdk)
ament_target_dependencies(scout_base_node rclcpp tf2 tf2_ros std_msgs nav_msgs sensor_msgs scout_msgs)
ament_target_dependencies(scout_base_node rclcpp tf2 tf2_ros tf2_geometry_msgs std_msgs nav_msgs sensor_msgs scout_msgs)

install(TARGETS scout_base_node
DESTINATION lib/${PROJECT_NAME})
Expand Down
2 changes: 1 addition & 1 deletion scout_base/include/scout_base/scout_messenger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <nav_msgs/msg/odometry.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>

#include "scout_msgs/msg/scout_status.hpp"
#include "scout_msgs/msg/scout_light_cmd.hpp"
Expand Down
16 changes: 8 additions & 8 deletions scout_base/src/scout_base_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,17 @@
namespace westonrobot {
ScoutBaseRos::ScoutBaseRos(std::string node_name)
: rclcpp::Node(node_name), keep_running_(false) {
this->declare_parameter("port_name");
this->declare_parameter("port_name", "can0");

this->declare_parameter("odom_frame");
this->declare_parameter("base_frame");
this->declare_parameter("odom_topic_name");
this->declare_parameter("odom_frame", "odom");
this->declare_parameter("base_frame", "base_link");
this->declare_parameter("odom_topic_name", "odom");

this->declare_parameter("is_scout_mini");
this->declare_parameter("is_omni_wheel");
this->declare_parameter("is_scout_mini", false);
this->declare_parameter("is_omni_wheel", false);

this->declare_parameter("simulated_robot");
this->declare_parameter("control_rate");
this->declare_parameter("simulated_robot", false);
this->declare_parameter("control_rate", 50);

LoadParameters();
}
Expand Down