34 #include <gtest/gtest.h> 41 #define DBG_MSG( ... ) printf( __VA_ARGS__ ); printf("\n"); 42 #define DBG_MSG_STREAM( ... ) std::cout << __VA_ARGS__ << std::endl; 54 typedef visualization_msgs::InteractiveMarkerInitConstPtr
InitConstPtr;
86 const std::string& server_id,
87 const std::string& msg )
94 void resetCb(
const std::string& server_id )
96 DBG_MSG(
"resetCb( %s ) called", server_id.c_str() );
103 for(
int i=0;i<10;i++)
110 TEST(InteractiveMarkerServerAndClient, connect_tf_error)
116 visualization_msgs::InteractiveMarker int_marker;
117 int_marker.name =
"marker1";
118 int_marker.header.frame_id =
"valid_frame";
131 DBG_MSG(
"----------------------------------------");
133 server.
insert(int_marker);
142 ASSERT_EQ( 1,
init_msg->markers.size() );
143 ASSERT_EQ(
"marker1",
init_msg->markers[0].name );
144 ASSERT_EQ(
"valid_frame",
init_msg->markers[0].header.frame_id );
147 DBG_MSG(
"----------------------------------------");
151 int_marker.name =
"marker2";
153 server.
insert(int_marker);
165 ASSERT_EQ(
"marker2",
update_msg->markers[0].name );
168 DBG_MSG(
"----------------------------------------");
172 int_marker.header.frame_id =
"invalid_frame";
174 server.
insert(int_marker);
182 ASSERT_TRUE(
reset_server_id.find(
"/test_server") != std::string::npos );
185 DBG_MSG(
"----------------------------------------");
193 int_marker.header.frame_id =
"valid_frame";
195 server.
insert(int_marker);
205 DBG_MSG(
"----------------------------------------");
209 server.
erase(
"marker1");
221 ASSERT_EQ(
"marker1",
update_msg->erases[0] );
224 DBG_MSG(
"----------------------------------------");
228 server.
setPose(
"marker2", int_marker.pose, int_marker.header );
240 ASSERT_EQ(
"marker2",
update_msg->poses[0].name );
245 int main(
int argc,
char **argv)
247 ros::init(argc, argv,
"im_server_client_test");
248 testing::InitGoogleTest(&argc, argv);
249 return RUN_ALL_TESTS();
int main(int argc, char **argv)
UpdateConstPtr update_msg
void statusCb(InteractiveMarkerClient::StatusT status, const std::string &server_id, const std::string &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
void setInitCb(const InitCallback &cb)
Set callback for init messages.
std::string reset_server_id
TEST(InteractiveMarkerServerAndClient, connect_tf_error)
void setResetCb(const ResetCallback &cb)
Set callback for resetting one server connection.
void setUpdateCb(const UpdateCallback &cb)
Set callback for update messages.
void setStatusCb(const StatusCallback &cb)
Set callback for status updates.
visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr
void initCb(const InitConstPtr &msg)
void insert(const visualization_msgs::InteractiveMarker &int_marker)
void update()
Update tf info, call callbacks.
void resetCb(const std::string &server_id)
bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
ROSCPP_DECL void spinOnce()
bool erase(const std::string &name)
void updateCb(const UpdateConstPtr &msg)
#define DBG_MSG_STREAM(...)
visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr