Go to the documentation of this file.
34 #include <gtest/gtest.h>
44 #define DBG_MSG( ... ) printf( __VA_ARGS__ ); printf("\n");
45 #define DBG_MSG_STREAM( ... ) std::cout << __VA_ARGS__ << std::endl;
57 typedef visualization_msgs::InteractiveMarkerInitConstPtr
InitConstPtr;
89 const std::string& server_id,
90 const std::string& msg )
97 void resetCb(
const std::string& server_id )
99 DBG_MSG(
"resetCb( %s ) called", server_id.c_str() );
106 for(
int i=0;i<10;i++)
109 std::this_thread::sleep_for(std::chrono::microseconds(1000));
113 TEST(InteractiveMarkerServerAndClient, connect_tf_error)
119 visualization_msgs::InteractiveMarker int_marker;
120 int_marker.name =
"marker1";
121 int_marker.header.frame_id =
"valid_frame";
134 DBG_MSG(
"----------------------------------------");
136 server.insert(int_marker);
145 ASSERT_EQ( 1,
init_msg->markers.size() );
146 ASSERT_EQ(
"marker1",
init_msg->markers[0].name );
147 ASSERT_EQ(
"valid_frame",
init_msg->markers[0].header.frame_id );
150 DBG_MSG(
"----------------------------------------");
154 int_marker.name =
"marker2";
156 server.insert(int_marker);
168 ASSERT_EQ(
"marker2",
update_msg->markers[0].name );
171 DBG_MSG(
"----------------------------------------");
175 int_marker.header.frame_id =
"invalid_frame";
177 server.insert(int_marker);
185 ASSERT_TRUE(
reset_server_id.find(
"/test_server") != std::string::npos );
188 DBG_MSG(
"----------------------------------------");
190 std::this_thread::sleep_for(std::chrono::microseconds(2000000));
196 int_marker.header.frame_id =
"valid_frame";
198 server.insert(int_marker);
208 DBG_MSG(
"----------------------------------------");
224 ASSERT_EQ(
"marker1",
update_msg->erases[0] );
227 DBG_MSG(
"----------------------------------------");
231 server.setPose(
"marker2", int_marker.pose, int_marker.header );
243 ASSERT_EQ(
"marker2",
update_msg->poses[0].name );
248 int main(
int argc,
char **argv)
250 ros::init(argc, argv,
"im_server_client_test");
251 testing::InitGoogleTest(&argc, argv);
252 return RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
INTERACTIVE_MARKERS_PUBLIC void setResetCb(const ResetCallback &cb)
Set callback for resetting one server connection.
void updateCb(const UpdateConstPtr &msg)
TEST(InteractiveMarkerServerAndClient, connect_tf_error)
INTERACTIVE_MARKERS_PUBLIC void setInitCb(const InitCallback &cb)
Set callback for init messages.
ROSCPP_DECL void spinOnce()
std::string reset_server_id
UpdateConstPtr update_msg
void statusCb(InteractiveMarkerClient::StatusT status, const std::string &server_id, const std::string &msg)
visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr
visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr
void initCb(const InitConstPtr &msg)
INTERACTIVE_MARKERS_PUBLIC void update()
Update tf info, call callbacks.
void resetCb(const std::string &server_id)
INTERACTIVE_MARKERS_PUBLIC void setUpdateCb(const UpdateCallback &cb)
Set callback for update messages.
INTERACTIVE_MARKERS_PUBLIC void setStatusCb(const StatusCallback &cb)
Set callback for status updates.
boost::shared_ptr< interactive_markers::InteractiveMarkerServer > server
#define DBG_MSG_STREAM(...)
int main(int argc, char **argv)
interactive_markers
Author(s): David Gossow, William Woodall
autogenerated on Fri Oct 27 2023 02:31:54