Skip to content

Commit

Permalink
add test for internal messaging
Browse files Browse the repository at this point in the history
  • Loading branch information
esquires committed Jul 24, 2018
1 parent b916e9f commit c9eb7c9
Show file tree
Hide file tree
Showing 6 changed files with 97 additions and 25 deletions.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -267,6 +267,7 @@ add_dependencies(entity scrimmage_ros_generate_messages_cpp)
## Mark other files for installation (e.g. launch and bag files, etc.)
install(FILES
test/test_auction.launch
test/test_auction2.launch
# myfile2
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
Expand All @@ -288,4 +289,7 @@ if(CATKIN_ENABLE_TESTING)

add_rostest_gtest(test_auction test/test_auction.launch test/test_auction.cpp)
target_link_libraries(test_auction ${catkin_LIBRARIES} scrimmage-core scrimmage-python gtest_main)

add_rostest_gtest(test_auction2 test/test_auction2.launch test/test_auction.cpp)
target_link_libraries(test_auction2 ${catkin_LIBRARIES} scrimmage-core scrimmage-python gtest_main)
endif()
1 change: 1 addition & 0 deletions launch/auction.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
name="entity_1"
type="auctioneer"
output="screen">
<param name="wrap_all" value="true" type="bool"/>
<param name="mission_file" value="$(arg mission_file)" type="str"/>
<param name="max_contacts" value="$(arg max_contacts)" type="int"/>
<param name="entity_name" value="agent" type="str"/>
Expand Down
50 changes: 33 additions & 17 deletions src/auctioneer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,23 +112,39 @@ int main(int argc, char **argv) {

const std::string network_name = "CommsNetwork";

ros::Publisher pub_start_auction =
nh.advertise<RosStartAuction>("StartAuction", 1000);
external.pub_cb<auction::StartAuction>(network_name, "StartAuction",
sc2ros_start_auction, pub_start_auction);

ros::Publisher pub_bid_auction =
nh.advertise<RosBidAuction>("BidAuction", 1000);
external.pub_cb<auction::BidAuction>(network_name, "BidAuction",
sc2ros_bid_auction, pub_bid_auction);

ros::Subscriber sub_start_auction = nh.subscribe("StartAuction", 1000,
external.sub_cb<RosStartAuction>(network_name, "StartAuction",
ros2sc_start_auction));

ros::Subscriber sub_bid_auction = nh.subscribe("BidAuction", 1000,
external.sub_cb<RosBidAuction>(network_name, "BidAuction",
ros2sc_bid_auction));
bool wrap_all;
private_nh.param("wrap_all", wrap_all, true);
std::cout << "wrap_all = " << wrap_all << std::endl;

ros::Publisher pub_start_auction;
ros::Publisher pub_bid_auction;
ros::Publisher pub_result_auction;

ros::Subscriber sub_start_auction;
ros::Subscriber sub_bid_auction;

if (wrap_all) {
pub_start_auction = nh.advertise<RosStartAuction>("StartAuction", 1000);
external.pub_cb<auction::StartAuction>(
network_name, "StartAuction", sc2ros_start_auction, pub_start_auction);

pub_bid_auction = nh.advertise<RosBidAuction>("BidAuction", 1000);
external.pub_cb<auction::BidAuction>(
network_name, "BidAuction", sc2ros_bid_auction, pub_bid_auction);

sub_start_auction = nh.subscribe("StartAuction", 1000,
external.sub_cb<RosStartAuction>(
network_name, "StartAuction", ros2sc_start_auction));

sub_bid_auction = nh.subscribe("BidAuction", 1000,
external.sub_cb<RosBidAuction>(
network_name, "BidAuction", ros2sc_bid_auction));
}

pub_result_auction = nh.advertise<RosBidAuction>("ResultAuction", 1000);
external.pub_cb<auction::BidAuction>(
network_name, "ResultAuction", sc2ros_bid_auction, pub_result_auction);


const double loop_rate_hz = 10;
const double startup_delay = 1;
Expand Down
30 changes: 24 additions & 6 deletions test/test_auction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,17 +42,31 @@ using scrimmage_ros::RosBidAuction;
class AuctionTest : public testing::Test {
protected:
virtual void SetUp() {
ros::NodeHandle private_nh("~");
ros::NodeHandle nh_;
sub_start_ =
nh_.subscribe("StartAuction", 20,
&AuctionTest::start_auction_callback, this);
sub_bid_ =
nh_.subscribe("BidAuction", 20,
&AuctionTest::bid_auction_callback, this);

sub_result_ =
nh_.subscribe("ResultAuction", 20,
&AuctionTest::result_auction_callback, this);

private_nh.param("num_bids", num_bids_, 5000);
private_nh.param("num_starts", num_starts_, 5000);
}

int num_bids_ = 5000;
int num_starts_ = 5000;

int start_hx_ct_ = 0;
int bid_hx_ct_ = 0;
int winner_id_ = -1;

ros::Subscriber sub_result_;
ros::Subscriber sub_start_;
ros::Subscriber sub_bid_;

Expand All @@ -64,6 +78,10 @@ class AuctionTest : public testing::Test {
void bid_auction_callback(const RosBidAuction::ConstPtr &/*msg*/) {
bid_hx_ct_ += 1;
}

void result_auction_callback(const RosBidAuction::ConstPtr &msg) {
winner_id_ = msg->sender_id;
}
};

TEST_F(AuctionTest, msg) {
Expand All @@ -72,13 +90,13 @@ TEST_F(AuctionTest, msg) {
loop_rate.sleep();
ros::spinOnce();

EXPECT_EQ(bid_hx_ct_, 2);
EXPECT_EQ(start_hx_ct_, 1);
EXPECT_EQ(bid_hx_ct_, num_bids_);
EXPECT_EQ(start_hx_ct_, num_starts_);
}

int main(int argc, char **argv) {
::testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "auction_test");
ros::start();
return RUN_ALL_TESTS();
::testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "auction_test");
ros::start();
return RUN_ALL_TESTS();
}
10 changes: 8 additions & 2 deletions test/test_auction.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
output="screen">

<param name="mission_file" value="$(arg mission_file)" type="str"/>
<param name="wrap_all" value="true" type="bool"/>
<param name="max_contacts" value="$(arg max_contacts)" type="int"/>
<param name="entity_name" value="agent" type="str"/>
<param name="entity_id" value="1" type="int"/>
Expand All @@ -19,14 +20,19 @@
type="auctioneer"
output="screen">
<param name="mission_file" value="$(arg mission_file)" type="str"/>
<param name="wrap_all" value="true" type="bool"/>
<param name="max_contacts" value="$(arg max_contacts)" type="int"/>
<param name="entity_name" value="agent" type="str"/>
<param name="entity_id" value="2" type="int"/>
</node>

<test
test-name="test_auction"
test-name="test_auction2"
pkg="scrimmage_ros"
type="test_auction" />
type="test_auction">

<param name="num_bids" value="2" type="int"/>
<param name="num_starts" value="1" type="int"/>
</test>

</launch>
27 changes: 27 additions & 0 deletions test/test_auction2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<launch>

<arg name="mission_file" default="~/scrimmage/scrimmage/missions/auction_assign2.xml"/>
<arg name="max_contacts" default="100"/>

<node pkg="scrimmage_ros"
name="entity_1"
type="auctioneer"
output="screen">

<param name="mission_file" value="$(arg mission_file)" type="str"/>
<param name="wrap_all" value="false" type="bool"/>
<param name="max_contacts" value="$(arg max_contacts)" type="int"/>
<param name="entity_name" value="agent" type="str"/>
<param name="entity_id" value="1" type="int"/>
</node>

<test
test-name="test_auction2"
pkg="scrimmage_ros"
type="test_auction">

<param name="num_bids" value="0" type="int"/>
<param name="num_starts" value="0" type="int"/>

</test>
</launch>

0 comments on commit c9eb7c9

Please sign in to comment.