Skip to content
Snippets Groups Projects
Commit 5593e96d authored by Johannes Mey's avatar Johannes Mey
Browse files

send the scene more frequently, restart the scene provider when it crashes

parent 0720e3a3
Branches
No related tags found
No related merge requests found
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
<arg name="connection_address" default="tcp://*:6576" doc="connection address for NNG scene-based selection"/> <arg name="connection_address" default="tcp://*:6576" doc="connection address for NNG scene-based selection"/>
<arg name="mqtt_server" default="tcp://127.0.0.1:1883" doc="MQTT server for communication with client cells"/> <arg name="mqtt_server" default="tcp://127.0.0.1:1883" doc="MQTT server for communication with client cells"/>
<node pkg="ccf_immersive_sorting" type="virtual_scene_provider" name="main_controller" output="screen"> <node pkg="ccf_immersive_sorting" type="virtual_scene_provider" name="main_controller" output="screen" respawn="true" respawn_delay="3">
<param name="connection_address" type="string" value="$(arg connection_address)"/> <param name="connection_address" type="string" value="$(arg connection_address)"/>
<param name="mqtt_server" type="yaml" value="$(arg mqtt_server)"/> <param name="mqtt_server" type="yaml" value="$(arg mqtt_server)"/>
<param name="arm" type="string" value="virtual-arm"/> <param name="arm" type="string" value="virtual-arm"/>
......
...@@ -62,25 +62,21 @@ int main(int argc, char **argv) ...@@ -62,25 +62,21 @@ int main(int argc, char **argv)
controller.addConnection(client_connection); controller.addConnection(client_connection);
client_connection->listen(getParameter<std::string>(n, "topics/selection", "selection")); client_connection->listen(getParameter<std::string>(n, "topics/selection", "selection"));
auto fallback_path = ros::package::getPath("ccf_immersive_sorting") + "/config/config_scene_virtual-tag-table-grey.json"; auto fallback_path =
ros::package::getPath("ccf_immersive_sorting") + "/config/config_scene_virtual-tag-table-grey.json";
controller.loadScene(getPrivateParameter<std::string>("scene", fallback_path)); controller.loadScene(getPrivateParameter<std::string>("scene", fallback_path));
Object *robot = controller.resolveObject(controller.getRobotName());
Object* selected_box = nullptr; Object* selected_box = nullptr;
Object* selected_bin = nullptr; Object* selected_bin = nullptr;
ros::Subscriber sub = n.subscribe<std_msgs::Empty>( ros::Subscriber sub = n.subscribe<std_msgs::Empty>(
"send_scene", 1000, [&controller](const std_msgs::EmptyConstPtr &msg) "send_scene", 1000, [&controller](const std_msgs::EmptyConstPtr& msg) { controller.sendScene(); });
{ controller.sendScene(); }); ros::Timer timer = n.createTimer(ros::Duration(3), [&controller](const ros::TimerEvent& event) {
ros::Timer timer = n.createTimer(ros::Duration(10), [&controller](const ros::TimerEvent &event)
{
controller.sendScene(); controller.sendScene();
}); // send a scene every ten seconds }); // send a scene every three seconds
auto selection_message_callback =
[&controller, &selected_box, &selected_bin, client_connection](const Selection &selection)
{
auto selection_message_callback = [&controller, &selected_box, &selected_bin,
client_connection](const Selection& selection) {
client_connection->send("vr_selection", selection.SerializeAsString()); client_connection->send("vr_selection", selection.SerializeAsString());
Object* object = controller.resolveObject(selection.id()); Object* object = controller.resolveObject(selection.id());
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment