Skip to content

Commit

Permalink
Use node logging in warehouse broadcast (#2432)
Browse files Browse the repository at this point in the history
(cherry picked from commit 6d2eaab)
  • Loading branch information
tylerjw authored and mergify[bot] committed Oct 12, 2023
1 parent e538316 commit e8e0c47
Showing 1 changed file with 7 additions and 8 deletions.
15 changes: 7 additions & 8 deletions moveit_ros/warehouse/src/broadcast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@ static const std::string CONSTRAINTS_TOPIC = "constraints";

static const std::string STATES_TOPIC = "robot_states";

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.broadcast");

using namespace std::chrono_literals;

int main(int argc, char** argv)
Expand All @@ -70,6 +68,7 @@ int main(int argc, char** argv)
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("publish_warehouse_data", node_options);
const auto logger = node->get_logger();

// time to wait in between publishing messages
double delay = 0.001;
Expand Down Expand Up @@ -136,7 +135,7 @@ int main(int argc, char** argv)
moveit_warehouse::PlanningSceneWithMetadata pswm;
if (pss.getPlanningScene(pswm, scene_name))
{
RCLCPP_INFO(LOGGER, "Publishing scene '%s'",
RCLCPP_INFO(logger, "Publishing scene '%s'",
pswm->lookupString(moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME).c_str());
pub_scene->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
executor.spin_once(0ns);
Expand All @@ -149,14 +148,14 @@ int main(int argc, char** argv)
std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
std::vector<std::string> query_names;
pss.getPlanningQueries(planning_queries, query_names, pswm->name);
RCLCPP_INFO(LOGGER, "There are %d planning queries associated to the scene",
RCLCPP_INFO(logger, "There are %d planning queries associated to the scene",
static_cast<int>(planning_queries.size()));
rclcpp::sleep_for(500ms);
for (std::size_t i = 0; i < planning_queries.size(); ++i)
{
if (req)
{
RCLCPP_INFO(LOGGER, "Publishing query '%s'", query_names[i].c_str());
RCLCPP_INFO(logger, "Publishing query '%s'", query_names[i].c_str());
pub_req->publish(static_cast<const moveit_msgs::msg::MotionPlanRequest&>(*planning_queries[i]));
executor.spin_once(0ns);
}
Expand Down Expand Up @@ -190,7 +189,7 @@ int main(int argc, char** argv)
moveit_warehouse::ConstraintsWithMetadata cwm;
if (cs.getConstraints(cwm, cname))
{
RCLCPP_INFO(LOGGER, "Publishing constraints '%s'",
RCLCPP_INFO(logger, "Publishing constraints '%s'",
cwm->lookupString(moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME).c_str());
pub_constr->publish(static_cast<const moveit_msgs::msg::Constraints&>(*cwm));
executor.spin_once(0ns);
Expand All @@ -212,7 +211,7 @@ int main(int argc, char** argv)
moveit_warehouse::RobotStateWithMetadata rswm;
if (rs.getRobotState(rswm, rname))
{
RCLCPP_INFO(LOGGER, "Publishing state '%s'",
RCLCPP_INFO(logger, "Publishing state '%s'",
rswm->lookupString(moveit_warehouse::RobotStateStorage::STATE_NAME).c_str());
pub_state->publish(static_cast<const moveit_msgs::msg::RobotState&>(*rswm));
executor.spin_once(0ns);
Expand All @@ -222,7 +221,7 @@ int main(int argc, char** argv)
}

rclcpp::sleep_for(1s);
RCLCPP_INFO(LOGGER, "Done.");
RCLCPP_INFO(logger, "Done.");

return 0;
}

0 comments on commit e8e0c47

Please sign in to comment.