Skip to content

Commit

Permalink
Compiles fully
Browse files Browse the repository at this point in the history
  • Loading branch information
ana-GT committed Oct 29, 2024
1 parent c7c18ad commit 6b7d484
Show file tree
Hide file tree
Showing 13 changed files with 59 additions and 38 deletions.
2 changes: 0 additions & 2 deletions communications/ff_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@ find_package(builtin_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(actionlib_msgs REQUIRED)
find_package(diagnostic_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(trajectory_msgs REQUIRED)
Expand Down Expand Up @@ -69,7 +68,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}
geometry_msgs
sensor_msgs
trajectory_msgs
actionlib_msgs
diagnostic_msgs
tf2_geometry_msgs

Expand Down
2 changes: 0 additions & 2 deletions communications/ff_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
<build_depend>geometry_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>trajectory_msgs</build_depend>
<build_depend>actionlib_msgs</build_depend>
<build_depend>diagnostic_msgs</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>

Expand All @@ -33,7 +32,6 @@
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>trajectory_msgs</exec_depend>
<exec_depend>actionlib_msgs</exec_depend>

<test_depend>ament_lint_common</test_depend>

Expand Down
4 changes: 2 additions & 2 deletions management/executive/include/executive/executive.h
Original file line number Diff line number Diff line change
Expand Up @@ -248,12 +248,12 @@ class Executive : public ff_util::FreeFlyerComponent {
bool SetEnableAutoReturn(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetEnableImmediate(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetEnableReplan(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetExposure(ff_msgs::msg::CommandStamped::SharedPtr const& cmd);
bool SetExposure(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetFlashlightBrightness(
ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetHolonomicMode(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetInertia(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetMap(ff_msgs::msg::CommandStamped::SharedPtr const& cmd);
bool SetMap(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetOperatingLimits(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetPlan(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
bool SetPlanner(ff_msgs::msg::CommandStamped::SharedPtr const cmd);
Expand Down
18 changes: 9 additions & 9 deletions management/executive/src/executive.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2666,8 +2666,8 @@ bool Executive::SetExposure(ff_msgs::msg::CommandStamped::SharedPtr const cmd) {
err_msg = "Malformed arguments for set exposure command!";
completed_status = ff_msgs::msg::AckCompletedStatus::BAD_SYNTAX;
} else {
ff_msgs::srv::SetExposure set_exposure_srv;
set_exposure_srv.request.exposure = cmd->args[1].f;
ff_util::FreeFlyerService<ff_msgs::srv::SetExposure> set_exposure_srv;
set_exposure_srv.request->exposure = cmd->args[1].f;
if (cmd->args[0].s == CommandConstants::PARAM_NAME_CAMERA_NAME_DOCK) {
// Check to make sure the dock camera exposure service is valid
if (!set_dock_cam_exposure_client_.exists()) {
Expand All @@ -2678,7 +2678,7 @@ bool Executive::SetExposure(ff_msgs::msg::CommandStamped::SharedPtr const cmd) {
if (!set_dock_cam_exposure_client_.call(set_exposure_srv)) {
err_msg = "Failed to set dock cam exposure.";
} else {
if (set_exposure_srv.response.success) {
if (set_exposure_srv.response->success) {
successful = true;
completed_status = ff_msgs::msg::AckCompletedStatus::OK;
}
Expand All @@ -2694,7 +2694,7 @@ bool Executive::SetExposure(ff_msgs::msg::CommandStamped::SharedPtr const cmd) {
if (!set_nav_cam_exposure_client_.call(set_exposure_srv)) {
err_msg = "Failed to set nav cam exposure.";
} else {
if (set_exposure_srv.response.success) {
if (set_exposure_srv.response->success) {
successful = true;
completed_status = ff_msgs::msg::AckCompletedStatus::OK;
}
Expand Down Expand Up @@ -2881,17 +2881,17 @@ bool Executive::SetMap(ff_msgs::msg::CommandStamped::SharedPtr const cmd) {
return false;
}

ff_msgs::srv::ResetMap map_srv;
ff_util::FreeFlyerService<ff_msgs::srv::ResetMap> map_srv;
// Extract map path and name
map_srv.request.map_file = cmd->args[0].s;
map_srv.request->map_file = cmd->args[0].s;

if (!CheckServiceExists(reset_map_client_, "Reset map", cmd->cmd_id)) {
if (!CheckServiceExists(reset_map_client_.exists(), "Reset map", cmd->cmd_id)) {
return false;
}

if (!reset_map_client_.call(map_srv)) {
state_->AckCmd(cmd->cmd_id,
ff_msgs::AckCompletedStatus::EXEC_FAILED,
ff_msgs::msg::AckCompletedStatus::EXEC_FAILED,
"Reset map service returned false!");
return false;
}
Expand Down Expand Up @@ -4210,7 +4210,7 @@ bool Executive::ReadParams() {

if (!config_params_.GetBool("sys_monitor_heartbeat_fault_blocking",
&sys_monitor_heartbeat_fault_blocking_)) {
err_msg == "Sys monitor heartbeat fault blocking not specified.";
err_msg = "Sys monitor heartbeat fault blocking not specified.";
FF_ERROR("%s", err_msg.c_str());
this->AssertFault(ff_util::INITIALIZATION_FAILED, err_msg);
return false;
Expand Down
2 changes: 1 addition & 1 deletion management/executive/tools/data_to_disk_pub.cc
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ void TimerCallback() {
int main(int argc, char** argv) {
ff_common::InitFreeFlyerApplication(&argc, &argv);
rclcpp::init(argc, argv);
NodeHandle nh;
NodeHandle nh = std::make_shared<rclcpp::Node>("data_to_disk_pub");

if (!google::RegisterFlagValidator(&FLAGS_compression, &ValidateCompression)) {
std::cerr << "Failed to register compression flag validator." << std::endl;
Expand Down
16 changes: 4 additions & 12 deletions management/executive/tools/plan_pub.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,6 @@ namespace io = boost::iostreams;

FF_DEFINE_LOGGER("plan_pub")

DEFINE_string(compression, "none",
"Type of compression [none, deflate, gzip]");

constexpr uintmax_t kMaxSize = 128 * 1024;

rclcpp::Time plan_pub_time;

Publisher<ff_msgs::msg::CommandStamped> command_pub;
Expand Down Expand Up @@ -93,13 +88,10 @@ void on_cf_ack(ff_msgs::msg::CompressedFileAck::SharedPtr const cf_ack) {

// If remote and in the granite lab, the clocks of the robots might not be
// properly synchronized because we do it manually
if (plan_pub_time <= cf_ack->header.stamp + duration(5.0)) {
if (plan_pub_time <= rclcpp::Time(cf_ack->header.stamp) + rclcpp::Duration::from_seconds(5.0)) {
FF_INFO("Compressed file ack is valid! Sending set plan!");
ff_msgs::msg::CommandStamped cmd;
cmd.cmd_name = ff_msgs::msg::CommandConstants::CMD_NAME_SET_PLAN;

if (plan_pub_time <= cf_ack->header.stamp + rclcpp::Duration(5.0)) {

cmd.subsys_name = "Astrobee";
command_pub->publish(cmd);
}
Expand All @@ -114,7 +106,7 @@ void on_plan_status(ff_msgs::msg::PlanStatusStamped::SharedPtr const ps) {

// If remote and in the granite lab, the clocks of the robots might not be
// properly synchronized because we do it manually
if (plan_pub_time <= ps->header.stamp + rclcpp::Duration(5.0)) {
if (plan_pub_time <= ps->header.stamp + rclcpp::Duration::from_seconds(5.0)) {
ff_msgs::msg::CommandStamped cmd;
cmd.cmd_name = ff_msgs::msg::CommandConstants::CMD_NAME_RUN_PLAN;
cmd.subsys_name = "Astrobee";
Expand All @@ -135,7 +127,7 @@ void TimerCallback() {
int main(int argc, char** argv) {
ff_common::InitFreeFlyerApplication(&argc, &argv);
rclcpp::init(argc, argv);
NodeHandle nh; // ros::NodeHandle n(std::string("/") + FLAGS_ns);
NodeHandle nh = std::make_shared<rclcpp::Node>("plan_pub"); // ros::NodeHandle n(std::string("/") + FLAGS_ns);

if (!google::RegisterFlagValidator(&FLAGS_compression, &ValidateCompression)) {
std::cerr << "Failed to register compression flag validator." << std::endl;
Expand Down Expand Up @@ -211,7 +203,7 @@ int main(int argc, char** argv) {
rclcpp::sleep_for(ns);
}
if (count == MAX_COUNT && !FLAGS_remote) {
ROS_ERROR("Could not connect");
FF_ERROR("Could not connect");
return 1;
}

Expand Down
2 changes: 1 addition & 1 deletion management/executive/tools/simple_move.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void AckCallback(ff_msgs::msg::AckStamped::SharedPtr const Ack) {

int main(int argc, char** argv) {
rclcpp::init(argc, argv);
NodeHandle nh;
NodeHandle nh = std::make_shared<rclcpp::Node>("simple_move");

if (argc <= 1) {
FF_ERROR("Error! Must provide x, y, and z as arguments!");
Expand Down
2 changes: 1 addition & 1 deletion management/executive/tools/teleop_tool.cc
Original file line number Diff line number Diff line change
Expand Up @@ -851,7 +851,7 @@ int main(int argc, char** argv) {
rclcpp::Time start_time = nh->now();

// Spin for 3 seconds
while (nh->now() - start_time < rclcpp::Duration(3.0))
while (nh->now() - start_time < rclcpp::Duration::from_seconds(3.0))
loop_rate.sleep();
}

Expand Down
2 changes: 1 addition & 1 deletion management/executive/tools/zones_pub.cc
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ void TimerCallback() {
int main(int argc, char** argv) {
ff_common::InitFreeFlyerApplication(&argc, &argv);
rclcpp::init(argc, argv);
NodeHandle nh;
NodeHandle nh = std::make_shared<rclcpp::Node>("zones_pub");

if (!google::RegisterFlagValidator(&FLAGS_compression, &ValidateCompression)) {
std::cerr << "Failed to register compression flag validator." << std::endl;
Expand Down
11 changes: 9 additions & 2 deletions mobility/choreographer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,15 @@
cmake_minimum_required(VERSION 3.5)
project(choreographer)

# Default to C++14
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()

set( CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Werror -O3 -fPIC" )

list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../../cmake")

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
Expand All @@ -41,13 +43,16 @@ find_package(nav_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)

find_package(JPS3D REQUIRED)

###########
## Build ##
###########

# Specify additional locations of header files
include_directories(
include
${JPS3D_INCLUDE_DIR}
)

# Declare C++ libraries
Expand All @@ -57,6 +62,7 @@ add_library(choreographer SHARED
)
target_compile_definitions(choreographer
PRIVATE "COMPOSITION_BUILDING_DLL")
target_link_libraries(choreographer ${JPS3D_LIBRARIES})
ament_target_dependencies(choreographer rclcpp rclcpp_components ff_common ff_util ff_msgs ff_hw_msgs jsonloader geometry_msgs nav_msgs visualization_msgs pcl_conversions)
rclcpp_components_register_nodes(choreographer "choreographer::ChoreographerComponent")

Expand Down Expand Up @@ -124,6 +130,7 @@ ament_export_dependencies(
ff_util
jsonloader
pcl_conversions
JPS3D
)

ament_export_include_directories(include)
Expand Down
13 changes: 13 additions & 0 deletions mobility/mapper/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,19 @@ endif()
#############
## Install ##
#############
ament_export_dependencies(
std_srvs
ff_util
ff_msgs
visualization_msgs
sensor_msgs
pcl_msgs
octomap
Eigen3
PCL
)

ament_export_include_directories(include)

# Mark libraries for installation
install(TARGETS ${PROJECT_NAME}
Expand Down
8 changes: 5 additions & 3 deletions mobility/mobility/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,14 @@
cmake_minimum_required(VERSION 3.5)
project(mobility)

# Default to C++14
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()
set( CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Werror -O3 -fPIC" )

list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../../cmake")

# Find amend and libraries
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
Expand Down Expand Up @@ -88,4 +90,4 @@ install(TARGETS teleop
# ERROR_QUIET
# )")

ament_package()
ament_package()
15 changes: 13 additions & 2 deletions mobility/planner_trapezoidal/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,13 @@
cmake_minimum_required(VERSION 3.5)
project(planner_trapezoidal)

# Default to C++14
# Default to C++17
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
endif()

set( CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -fPIC" )
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../../cmake")

## Find amend and libraries
find_package(ament_cmake REQUIRED)
Expand Down Expand Up @@ -69,6 +70,16 @@ rclcpp_components_register_nodes(${PROJECT_NAME} "planner_trapezoidal::PlannerTr
## Install ##
#############

ament_export_dependencies(
ff_common
ff_util
ff_msgs
choreographer
tf2_geometry_msgs
)

ament_export_include_directories(include)

target_include_directories(planner_trapezoidal
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
Expand Down

0 comments on commit 6b7d484

Please sign in to comment.