Skip to content

Commit 2550c10

Browse files
Isaac13 qol fixes + release 0.2.8 (#160)
* don't update focus if not needed + reset focus start panorama * make monitor exit cleanly * force stop if something happens to retry command; declutter output * update submodule * making berth names unique such that pos is not overwritten * make move output not flood the entire output * adding another \r * upping fsw version to only have one PR * reset focus for geometry too
1 parent f5cc1b4 commit 2550c10

File tree

12 files changed

+151
-84
lines changed

12 files changed

+151
-84
lines changed

RELEASE.md

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,10 @@
11
# Releases
22

3+
## Release 0.2.8
4+
5+
* Improvements to survey_manager output
6+
* Bug fixes
7+
38
## Release 0.2.7
49

510
* Survey manager

astrobee/behaviors/inspection/src/inspection_node.cc

Lines changed: 23 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -482,9 +482,9 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
482482
pub_guest_sci_.publish(cmd);
483483
}
484484

485-
void SendPicture(double focus_distance) {
486-
ROS_DEBUG_STREAM("Send picture");
487-
// Take picture
485+
486+
void SendSciCamCommand(std::string command) {
487+
// Chnage focus
488488
ff_msgs::CommandArg arg;
489489
std::vector<ff_msgs::CommandArg> cmd_args;
490490

@@ -496,7 +496,7 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
496496
cmd_args.push_back(arg);
497497

498498
arg.data_type = ff_msgs::CommandArg::DATA_TYPE_STRING;
499-
arg.s = "{\"name\": \"takePicture\", \"haz_dist\": " + std::to_string(focus_distance) +"}";
499+
arg.s = command;
500500
cmd_args.push_back(arg);
501501

502502
ff_msgs::CommandStamped cmd;
@@ -508,7 +508,12 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
508508
cmd.args = cmd_args;
509509

510510
pub_guest_sci_.publish(cmd);
511+
}
512+
511513

514+
void SendPicture(double focus_distance) {
515+
ROS_DEBUG_STREAM("Send picture");
516+
SendSciCamCommand("{\"name\": \"takePicture\", \"haz_dist\": " + std::to_string(focus_distance) +"}");
512517
// Timer for the sci cam camera
513518
sci_cam_timeout_.start();
514519
}
@@ -571,6 +576,8 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
571576
if (flashlight_intensity_current_ != cfg_.Get<double>("toggle_flashlight")) {
572577
flashlight_intensity_current_ = cfg_.Get<double>("toggle_flashlight");
573578
Flashlight(flashlight_intensity_current_);
579+
sci_cam_req_ = 1;
580+
SendPicture(-1);
574581
} else {
575582
// Move on in focus distance iteration
576583
flashlight_intensity_current_ = 0.0;
@@ -588,9 +595,9 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
588595
// When the anomaly detection returns a result it will go to the next inspection
589596
finished_anomaly_ = true;
590597
}
598+
sci_cam_req_ = 1;
599+
SendPicture(focus_distance_current_);
591600
}
592-
sci_cam_req_ = 1;
593-
SendPicture(focus_distance_current_);
594601
} else {
595602
return fsm_.Update(NEXT_INSPECT);
596603
}
@@ -748,14 +755,22 @@ class InspectionNode : public ff_util::FreeFlyerNodelet {
748755
// Geometry command
749756
case isaac_msgs::InspectionGoal::GEOMETRY:
750757
NODELET_DEBUG("Received Goal Geometry");
751-
if (inspection_->GenerateGeometrySurvey(goal_.inspect_poses))
758+
if (inspection_->GenerateGeometrySurvey(goal_.inspect_poses)) {
759+
// Reset the focus distance
760+
SendSciCamCommand("{\"name\": \"setFocusDistance\", \"distance\": " +
761+
std::to_string(cfg_.Get<double>("sci_cam_startup_focus")) + "}");
752762
return fsm_.Update(GOAL_INSPECT);
763+
}
753764
break;
754765
// Panorama command
755766
case isaac_msgs::InspectionGoal::PANORAMA:
756767
NODELET_DEBUG("Received Goal Panorama");
757-
if (inspection_->GeneratePanoramaSurvey(goal_.inspect_poses))
768+
if (inspection_->GeneratePanoramaSurvey(goal_.inspect_poses)) {
769+
// Reset the focus distance
770+
SendSciCamCommand("{\"name\": \"setFocusDistance\", \"distance\": " +
771+
std::to_string(cfg_.Get<double>("sci_cam_startup_focus")) + "}");
758772
return fsm_.Update(GOAL_INSPECT);
773+
}
759774
break;
760775
// Volumetric command
761776
case isaac_msgs::InspectionGoal::VOLUMETRIC:

astrobee/survey/survey_manager/data/granite_survey_static.yaml

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,14 +45,18 @@ bays_move:
4545
gra_bay5: ["-pos", "0.1 0.1 -0.68", "-att", "3.14 1 0 0"]
4646
gra_bay6: ["-pos", "0.1 -0.3 -0.68", "-att", "3.14 1 0 0"]
4747
gra_bay7: ["-pos", "0.1 -0.5 -0.68", "-att", "3.14 1 0 0"]
48-
berth1: ["-pos", "0.1 0.3 -0.68"]
49-
berth2: ["-pos", "0.1 -0.3 -0.68", "-att", "3.14 1 0 0"]
48+
berth1_g: ["-pos", "0.1 0.3 -0.68"]
49+
berth2_g: ["-pos", "0.1 -0.3 -0.68", "-att", "3.14 1 0 0"]
5050

5151

5252
bays_pano:
5353
gra_bay2: "panorama_granite_bsharp.txt"
5454
gra_bay6: "panorama_granite_wannabee.txt"
5555

56+
berth:
57+
berth1_g: "1"
58+
berth2_g: "2"
59+
5660
bogus_bays: [gra_bay0, gra_bay8]
5761
berths: [berth1, berth2]
5862
robots: [bsharp, wannabee]

astrobee/survey/survey_manager/data/jem_survey_dynamic.yaml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ goals:
3131
- {type: stereo, robot: bumble, order: 4, trajectory: jem_bay1_to_bay3}
3232
# This is one of the goals we previously had to comment out for POPF to return a halfway decent
3333
# plan. Adding a let_other_robot_reach goal mostly fixed the problem.
34-
- {type: robot_at, robot: bumble, location: berth1}
34+
- {type: robot_at, robot: bumble, location: berth1_g}
3535

3636
# This let_other_robot_reach goal is effectively a very specific kind of between-robot ordering
3737
# constraint. It tells honey to let bumble get to bay 5 before taking its first panorama. Without
@@ -45,10 +45,10 @@ goals:
4545
- {type: panorama, robot: honey, order: 3, location: jem_bay5}
4646
# This is the other objective we previously had to comment out for POPF to return a decent plan.
4747
- {type: stereo, robot: honey, order: 4, trajectory: jem_bay7_to_bay4}
48-
- {type: robot_at, robot: honey, location: berth2}
48+
- {type: robot_at, robot: honey, location: berth2_g}
4949

5050
init:
5151
bumble:
52-
location: berth1
52+
location: berth1_g
5353
honey:
54-
location: berth2
54+
location: berth2_g

astrobee/survey/survey_manager/pddl/problem_granite_survey.ps2.pddl

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -7,16 +7,16 @@ set instance gra_bay5 location
77
set instance gra_bay6 location
88
set instance gra_bay7 location
99
set instance gra_bay8 location
10-
set instance berth1 location
11-
set instance berth2 location
10+
set instance berth1_g location
11+
set instance berth2_g location
1212
set instance bsharp robot
1313
set instance wannabee robot
1414
set instance o0 order
1515
set instance o1 order
1616
set instance o2 order
1717
set instance o3 order
1818
set instance o4 order
19-
set goal (and (completed-panorama bsharp o0 gra_bay2) (completed-stereo bsharp o1 gra_bay1 gra_bay3) (robot-at bsharp berth1) (completed-panorama wannabee o1 gra_bay6) (completed-stereo wannabee o4 gra_bay5 gra_bay7) (robot-at wannabee berth2))
19+
set goal (and (completed-panorama bsharp o0 gra_bay2) (completed-stereo bsharp o1 gra_bay1 gra_bay3) (robot-at bsharp berth1_g) (completed-panorama wannabee o1 gra_bay6) (completed-stereo wannabee o4 gra_bay5 gra_bay7) (robot-at wannabee berth2_g))
2020
set predicate (move-connected gra_bay0 gra_bay1)
2121
set predicate (move-connected gra_bay1 gra_bay0)
2222
set predicate (move-connected gra_bay1 gra_bay2)
@@ -40,8 +40,8 @@ set predicate (location-real gra_bay4)
4040
set predicate (location-real gra_bay5)
4141
set predicate (location-real gra_bay6)
4242
set predicate (location-real gra_bay7)
43-
set predicate (dock-connected gra_bay3 berth1)
44-
set predicate (dock-connected gra_bay5 berth2)
43+
set predicate (dock-connected gra_bay3 berth1_g)
44+
set predicate (dock-connected gra_bay5 berth2_g)
4545
set predicate (robots-different bsharp wannabee)
4646
set predicate (robots-different wannabee bsharp)
4747
set predicate (locations-different gra_bay0 gra_bay1)
@@ -118,8 +118,8 @@ set predicate (locations-different gra_bay8 gra_bay6)
118118
set predicate (locations-different gra_bay8 gra_bay7)
119119
set predicate (robot-available bsharp)
120120
set predicate (robot-available wannabee)
121-
set predicate (robot-at bsharp berth1)
122-
set predicate (robot-at wannabee berth2)
121+
set predicate (robot-at bsharp berth1_g)
122+
set predicate (robot-at wannabee berth2_g)
123123
set predicate (location-available gra_bay0)
124124
set predicate (location-available gra_bay1)
125125
set predicate (location-available gra_bay2)

astrobee/survey/survey_manager/src/isaac_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -207,7 +207,8 @@ void IsaacAction::do_work() {
207207
progress_ = (ros::Time::now() - start_time_).toSec() / action_duration_;
208208
send_feedback(progress_, command_ + " running");
209209

210-
printf("\t ** %s [%5.1f%%] \n", command_.c_str(), progress_ * 100.0);
210+
// Status gets printed on terminal
211+
// printf("\t ** %s [%5.1f%%] \n", command_.c_str(), progress_ * 100.0);=
211212
int status;
212213
int result = waitpid(-1, &status, WNOHANG);
213214
// printf("Result: %d %d %d\n", result, pid_, status);

astrobee/survey/survey_manager/src/survey_manager/command_astrobee.py

Lines changed: 35 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -183,26 +183,27 @@ def __del__(self):
183183
self.sock_output.close()
184184

185185
def write_output_once(self, output):
186-
while not self.sock_output_connected:
186+
while not self._stop_event.is_set():
187187
try:
188-
# If socket is not connected try to connect
189-
self.sock_output_conn, addr = self.sock_output.accept()
190-
self.sock_output_conn.setblocking(False)
188+
if not self.sock_output_connected:
189+
# If socket is not connected try to connect
190+
self.sock_output_conn, addr = self.sock_output.accept()
191+
self.sock_output_conn.setblocking(False)
191192

192-
self.sock_output_connected = True
193+
self.sock_output_connected = True
193194
except socket.timeout:
194195
continue
195196

196-
try:
197-
if self.sock_output_connected:
198-
encoded_message = output.encode("ascii", errors="replace")
199-
for i in range(0, len(encoded_message), CHUNK_SIZE):
200-
chunk = encoded_message[i : i + CHUNK_SIZE]
201-
self.sock_output_conn.sendall(chunk)
202-
203-
except (socket.error, BrokenPipeError):
204-
loginfo("Error sending data. Receiver may have disconnected.")
205-
self.sock_output_connected = False
197+
try:
198+
if self.sock_output_connected:
199+
encoded_message = output.encode("ascii", errors="replace")
200+
for i in range(0, len(encoded_message), CHUNK_SIZE):
201+
chunk = encoded_message[i : i + CHUNK_SIZE]
202+
self.sock_output_conn.sendall(chunk)
203+
break
204+
except (socket.error, BrokenPipeError):
205+
loginfo("Error sending data. Receiver may have disconnected.")
206+
self.sock_output_connected = False
206207

207208
def thread_write_output(self, process):
208209
# loginfo("starting thread_write_output...")
@@ -218,13 +219,13 @@ def thread_write_output(self, process):
218219
if output == "":
219220
continue
220221
if output and not output.startswith("pos: x:"):
221-
loginfo(f"writer received: {output}")
222222
output_total += output
223223

224224
try:
225225
# If socket is not connected try to connect
226226
if not self.sock_output_connected:
227-
# loginfo("trying to connect")
227+
if not output.startswith("pos: x:"):
228+
loginfo(f"writer received: {output}")
228229
self.sock_output_conn, addr = self.sock_output.accept()
229230
self.sock_output_conn.setblocking(False)
230231

@@ -258,9 +259,7 @@ def read_input_once(self) -> str:
258259
# loginfo("waiting for connection")
259260
try:
260261
self.sock_input_conn, addr = self.sock_input.accept()
261-
self.sock_input_conn.settimeout(
262-
1
263-
) # Set a timeout for socket operations
262+
self.sock_input_conn.settimeout(1)
264263
self.sock_input_connected = True
265264
break
266265
except socket.timeout:
@@ -270,11 +269,17 @@ def read_input_once(self) -> str:
270269
request = self.sock_input_conn.recv(CHUNK_SIZE).decode(
271270
"ascii", errors="replace"
272271
)
273-
return request
272+
if request:
273+
return request
274+
else:
275+
self.sock_input_connected = False
276+
break
277+
loginfo("request")
274278
except socket.timeout:
275279
continue
276280
except ConnectionResetError:
277281
# Connection was reset, set sock_input_connected to False
282+
loginfo("disconnected")
278283
self.sock_input_connected = False
279284
break
280285
return ""
@@ -311,6 +316,8 @@ def thread_read_input(self, process):
311316
# If broken pipe connect
312317
if not request:
313318
break
319+
if request == "stop":
320+
return
314321
loginfo("reader sending: " + request)
315322
process.stdin.write(request + "\n")
316323
process.stdin.flush()
@@ -347,7 +354,11 @@ def send_command(self, command):
347354
output_thread.start()
348355

349356
# When the process finishes, te output thread automatically closes
350-
while output_thread.is_alive() and process.poll() is None:
357+
while (
358+
output_thread.is_alive()
359+
and input_thread.is_alive()
360+
and process.poll() is None
361+
):
351362
rospy.sleep(1)
352363

353364
except Exception as e:
@@ -802,11 +813,12 @@ def survey_manager_executor_recursive(
802813
)
803814

804815
while exit_code != 0 and not rospy.is_shutdown():
816+
loginfo(f"Exit code non-zero: Do you want to repeat the survey? (yes/no/skip):")
805817
process_executor.write_output_once(
806818
"Exit code non-zero: Do you want to repeat the survey? (yes/no/skip): \n"
807819
)
808820
repeat = process_executor.read_input_once().lower()
809-
821+
loginfo(f"Got response: {repeat}")
810822
if repeat == "yes":
811823
run_number += 1
812824
exit_code = survey_manager_executor_recursive(

0 commit comments

Comments
 (0)