Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use node logging in warehouse broadcast (backport #2432) #2444

Merged
merged 1 commit into from
Oct 12, 2023
Merged
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
15 changes: 7 additions & 8 deletions moveit_ros/warehouse/src/broadcast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,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 @@ -75,6 +73,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 @@ -141,7 +140,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 @@ -154,14 +153,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 @@ -195,7 +194,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 @@ -217,7 +216,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 @@ -227,7 +226,7 @@ int main(int argc, char** argv)
}

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

return 0;
}
Loading