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 save_as_text #2435

Closed
Closed
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
18 changes: 9 additions & 9 deletions moveit_ros/warehouse/src/save_as_text.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,12 +52,11 @@

static const std::string ROBOT_DESCRIPTION = "robot_description";

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

typedef std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Quaternion> LinkConstraintPair;
typedef std::map<std::string, LinkConstraintPair> LinkConstraintMap;

void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, LinkConstraintMap& lcmap)
void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, LinkConstraintMap& lcmap,
const rclcpp::Logger& logger)
{
for (const moveit_msgs::msg::PositionConstraint& position_constraint : constraints.position_constraints)
{
Expand All @@ -75,7 +74,7 @@ void collectLinkConstraints(const moveit_msgs::msg::Constraints& constraints, Li
}
else
{
RCLCPP_WARN(LOGGER, "Orientation constraint for %s has no matching position constraint",
RCLCPP_WARN(logger, "Orientation constraint for %s has no matching position constraint",
orientation_constraint.link_name.c_str());
}
}
Expand All @@ -88,6 +87,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("save_warehouse_as_text", node_options);
const auto logger = node->get_logger();

boost::program_options::options_description desc;
desc.add_options()("help", "Show help message")("host", boost::program_options::value<std::string>(),
Expand Down Expand Up @@ -125,7 +125,7 @@ int main(int argc, char** argv)
moveit_warehouse::PlanningSceneWithMetadata pswm;
if (pss.getPlanningScene(pswm, scene_name))
{
RCLCPP_INFO(LOGGER, "Saving scene '%s'", scene_name.c_str());
RCLCPP_INFO(logger, "Saving scene '%s'", scene_name.c_str());
psm.getPlanningScene()->setPlanningSceneMsg(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
std::ofstream fout((scene_name + ".scene").c_str());
psm.getPlanningScene()->saveGeometryToStream(fout);
Expand Down Expand Up @@ -155,7 +155,7 @@ int main(int argc, char** argv)
qfout << robot_state_names.size() << '\n';
for (const std::string& robot_state_name : robot_state_names)
{
RCLCPP_INFO(LOGGER, "Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
RCLCPP_INFO(logger, "Saving start state %s for scene %s", robot_state_name.c_str(), scene_name.c_str());
qfout << robot_state_name << '\n';
moveit_warehouse::RobotStateWithMetadata robot_state;
rss.getRobotState(robot_state, robot_state_name);
Expand All @@ -172,14 +172,14 @@ int main(int argc, char** argv)
qfout << constraint_names.size() << '\n';
for (const std::string& constraint_name : constraint_names)
{
RCLCPP_INFO(LOGGER, "Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
RCLCPP_INFO(logger, "Saving goal %s for scene %s", constraint_name.c_str(), scene_name.c_str());
qfout << "link_constraint" << '\n';
qfout << constraint_name << '\n';
moveit_warehouse::ConstraintsWithMetadata constraints;
cs.getConstraints(constraints, constraint_name);

LinkConstraintMap lcmap;
collectLinkConstraints(*constraints, lcmap);
collectLinkConstraints(*constraints, lcmap, logger);
for (std::pair<const std::string, LinkConstraintPair>& iter : lcmap)
{
std::string link_name = iter.first;
Expand All @@ -198,7 +198,7 @@ int main(int argc, char** argv)
}
}

RCLCPP_INFO(LOGGER, "Done.");
RCLCPP_INFO(logger, "Done.");
rclcpp::spin(node);
return 0;
}
Loading