Skip to content

Commit

Permalink
Changed comms bridge config and changed debug output to info.
Browse files Browse the repository at this point in the history
  • Loading branch information
kbrowne15 committed Jan 11, 2024
1 parent 0d1c82b commit 3543d02
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 25 deletions.
12 changes: 6 additions & 6 deletions astrobee/config/communications/comms_bridge.config
Original file line number Diff line number Diff line change
Expand Up @@ -28,23 +28,23 @@ links = {
-- A single link entry has required fields "from" and "to" that specify the robot roles involved
-- in the link.
from = "Bumble", -- manager
to = "Wannabee", -- actor
to = "Honey", -- actor

-- The link entry has three optional fields: relay_forward (messages to be relayed only in the
-- `from` to `to` direction), relay_backward (to be relayed only in the `to` to `from` direction),
-- and relay_both (to be relayed in both directions). Providing all three fields gives the user
-- full directional control while minimizing repetition and copy/paste errors.
relay_forward = {
{in_topic = "beh/inspection/feedback"},
{in_topic = "beh/inspection/result"},
{in_topic = "beh/inspection/state"},
{in_topic = "honey/command", out_topic="command"},
},
relay_backward = {
{in_topic = "bumble/beh/inspection/cancel", out_topic = "beh/inspection/cancel"},
{in_topic = "bumble/beh/inspection/goal", out_topic = "beh/inspection/goal"},
{in_topic = "mgt/ack"},
{in_topic = "mob/motion/feedback"},
{in_topic = "beh/dock/feedback"},
},
relay_both = {
{in_topic = "mgt/executive/agent_state"},
{in_topic = "mgt/sys_monitor/state"},
},
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ class GenericRapidSub {
}

void operator() (T const* data) {
ROS_DEBUG("Received data for topic %s\n", subscribe_topic_.c_str());
ROS_INFO("Received data for topic %s\n", subscribe_topic_.c_str());
ros_pub_->ConvertData(data);
}

Expand Down
8 changes: 4 additions & 4 deletions communications/comms_bridge/src/comms_bridge_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,8 +223,8 @@ class CommsBridgeNodelet : public ff_util::FreeFlyerNodelet {
connection = rapid_connections_[i];
dds_topic_name = agent_name_ + "-" +
rapid::ext::astrobee::GENERIC_COMMS_ADVERTISEMENT_INFO_TOPIC;
ROS_DEBUG("Comms Bridge: DDS Sub DDS advertisement info topic name: %s\n",
dds_topic_name.c_str());
ROS_INFO("Comms Bridge: DDS Sub DDS advertisement info topic name: %s\n",
dds_topic_name.c_str());
advertisement_info_sub =
std::make_shared<ff::GenericRapidSub<rapid::ext::astrobee::GenericCommsAdvertisementInfo>>(
"AstrobeeGenericCommsAdvertisementInfoProfile",
Expand All @@ -235,8 +235,8 @@ class CommsBridgeNodelet : public ff_util::FreeFlyerNodelet {

dds_topic_name = agent_name_ + "-" +
rapid::ext::astrobee::GENERIC_COMMS_CONTENT_TOPIC;
ROS_DEBUG("Comms Bridge: DDS Sub DDS content topic name: %s\n",
dds_topic_name.c_str());
ROS_INFO("Comms Bridge: DDS Sub DDS content topic name: %s\n",
dds_topic_name.c_str());
content_sub = std::make_shared<ff::GenericRapidSub<rapid::ext::astrobee::GenericCommsContent>>(
"AstrobeeGenericCommsContentProfile",
dds_topic_name,
Expand Down
8 changes: 4 additions & 4 deletions communications/comms_bridge/src/generic_rapid_msg_ros_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@ void GenericRapidMsgRosPub::ConvertData(

const std::string output_topic = data->outputTopic;

ROS_DEBUG("Comms Bridge Nodelet: Received advertisement message for topic %s\n",
output_topic.c_str());
ROS_INFO("Comms Bridge Nodelet: Received advertisement message for topic %s\n",
output_topic.c_str());

AdvertisementInfo ad_info;
ad_info.latching = data->latching;
Expand All @@ -62,8 +62,8 @@ void GenericRapidMsgRosPub::ConvertData(

const std::string output_topic = data->outputTopic;

ROS_DEBUG("Comms Bridge Nodelet: Received content message for topic %s\n",
output_topic.c_str());
ROS_INFO("Comms Bridge Nodelet: Received content message for topic %s\n",
output_topic.c_str());

std::map<std::string, RelayTopicInfo>::iterator iter = m_relay_topics_.find(output_topic);
if (iter == m_relay_topics_.end()) {
Expand Down
10 changes: 5 additions & 5 deletions communications/comms_bridge/src/generic_rapid_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,16 +27,16 @@ GenericRapidPub::GenericRapidPub(std::string const& robot_name) :
std::string dds_topic_name;
dds_topic_name = robot_name + "-" +
rapid::ext::astrobee::GENERIC_COMMS_ADVERTISEMENT_INFO_TOPIC;
ROS_DEBUG("Comms Bridge: DDS Pub DDS advertisement info topic name: %s\n",
dds_topic_name.c_str());
ROS_INFO("Comms Bridge: DDS Pub DDS advertisement info topic name: %s\n",
dds_topic_name.c_str());
advertisement_info_supplier_.reset(
new GenericRapidPub::AdvertisementInfoSupplier(
dds_topic_name, "", "AstrobeeGenericCommsAdvertisementInfoProfile", ""));

dds_topic_name = robot_name + "-" +
rapid::ext::astrobee::GENERIC_COMMS_CONTENT_TOPIC;
ROS_DEBUG("Comms Bridge: DDS Publisher DDS content topic name: %s\n",
dds_topic_name.c_str());
ROS_INFO("Comms Bridge: DDS Publisher DDS content topic name: %s\n",
dds_topic_name.c_str());
content_supplier_.reset(new GenericRapidPub::ContentSupplier(
dds_topic_name, "", "AstrobeeGenericCommsContentProfile", ""));

Expand Down Expand Up @@ -108,7 +108,7 @@ void GenericRapidPub::ProcessAdvertisementInfo(std::string const& output_topic,
}

// Currently the ROS message definition can only by 8192 characters long
ROS_DEBUG("Definition is %i long\n", definition.size());
ROS_INFO("Definition is %i long\n", definition.size());
CopyString<rapid::ext::astrobee::String8K>(8192,
definition,
msg.msgDefinition,
Expand Down
10 changes: 5 additions & 5 deletions communications/comms_bridge/src/generic_ros_sub_rapid_pub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void GenericROSSubRapidPub::AddTopics(
// advertisement info and content message to each roboot that needs it
topic_mapping_[primary_out_topic] = it->second;
// Add topic to base class
ROS_DEBUG("Adding topic %s to base class.", in_topic.c_str());
ROS_INFO("Adding topic %s to base class.", in_topic.c_str());
addTopic(in_topic, primary_out_topic);
}
} else {
Expand Down Expand Up @@ -73,7 +73,7 @@ void GenericROSSubRapidPub::advertiseTopic(const RelayTopicInfo& relay_info) {
const AdvertisementInfo &info = relay_info.ad_info;
std::string out_topic = relay_info.out_topic, robot_name, robot_out_topic;

ROS_DEBUG("Received ros advertise topic for topic %s\n", out_topic.c_str());
ROS_INFO("Received ros advertise topic for topic %s\n", out_topic.c_str());

// Make sure we recognize the topic
if (topic_mapping_.find(out_topic) == topic_mapping_.end()) {
Expand All @@ -86,7 +86,7 @@ void GenericROSSubRapidPub::advertiseTopic(const RelayTopicInfo& relay_info) {
robot_name = topic_mapping_[out_topic][i].first;
robot_out_topic = topic_mapping_[out_topic][i].second;

ROS_DEBUG("Robot name: %s Robot out topic: %s\n", robot_name.c_str(), robot_out_topic.c_str());
ROS_INFO("Robot name: %s Robot out topic: %s\n", robot_name.c_str(), robot_out_topic.c_str());

// Check robot connection exists
if (robot_connections_.find(robot_name) == robot_connections_.end()) {
Expand All @@ -107,7 +107,7 @@ void GenericROSSubRapidPub::relayMessage(const RelayTopicInfo& topic_info,
ContentInfo const& content_info) {
std::string out_topic = topic_info.out_topic, robot_name, robot_out_topic;
unsigned int size;
ROS_DEBUG("Received ros content message for topic %s\n", out_topic.c_str());
ROS_INFO("Received ros content message for topic %s\n", out_topic.c_str());

// Make sure we recognize the topic
if (topic_mapping_.find(out_topic) == topic_mapping_.end()) {
Expand All @@ -120,7 +120,7 @@ void GenericROSSubRapidPub::relayMessage(const RelayTopicInfo& topic_info,
robot_name = topic_mapping_[out_topic][i].first;
robot_out_topic = topic_mapping_[out_topic][i].second;

ROS_DEBUG("Robot name: %s Robot out topic: %s\n", robot_name.c_str(), robot_out_topic.c_str());
ROS_INFO("Robot name: %s Robot out topic: %s\n", robot_name.c_str(), robot_out_topic.c_str());

// Check robot connection exists
if (robot_connections_.find(robot_name) == robot_connections_.end()) {
Expand Down

0 comments on commit 3543d02

Please sign in to comment.