Skip to content

Commit

Permalink
formatting problems
Browse files Browse the repository at this point in the history
  • Loading branch information
JonasFrey96 committed Aug 16, 2023
1 parent 5205a04 commit 467149e
Show file tree
Hide file tree
Showing 3 changed files with 35 additions and 10 deletions.
25 changes: 20 additions & 5 deletions scripts/dataset_generation/extract_binary_images_and_labels.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,11 @@ def do(n, dry_run):

valid_topics = ["/state_estimator/anymal_state", "/wide_angle_camera_front/img_out"]

rosbags = ["/home/rschmid/RosBags/6/images.bag",
"/home/rschmid/RosBags/6/2023-03-02-11-13-08_anymal-d020-lpc_mission_0.bag",
"/home/rschmid/RosBags/6/2023-03-02-11-13-08_anymal-d020-lpc_mission_1.bag"]
rosbags = [
"/home/rschmid/RosBags/6/images.bag",
"/home/rschmid/RosBags/6/2023-03-02-11-13-08_anymal-d020-lpc_mission_0.bag",
"/home/rschmid/RosBags/6/2023-03-02-11-13-08_anymal-d020-lpc_mission_1.bag",
]

output_bag_wvn = s + "_wvn.bag"
output_bag_tf = s + "_tf.bag"
Expand Down Expand Up @@ -115,7 +117,20 @@ def do(n, dry_run):
info_msg.distortion_model = "equidistant"
info_msg.D = [0.4316922809468283, 0.09279900476637248, -0.4010909691803734, 0.4756163338479413]
info_msg.K = [575.6050407221768, 0.0, 745.7312198525915, 0.0, 578.564849365178, 519.5207040671075, 0.0, 0.0, 1.0]
info_msg.P = [575.6050407221768, 0.0, 745.7312198525915, 0.0, 0.0, 578.564849365178, 519.5207040671075, 0.0, 0.0, 0.0, 1.0, 0.0]
info_msg.P = [
575.6050407221768,
0.0,
745.7312198525915,
0.0,
0.0,
578.564849365178,
519.5207040671075,
0.0,
0.0,
0.0,
1.0,
0.0,
]
info_msg.R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]

rosbag_info_dict = get_bag_info(output_bag_wvn)
Expand Down Expand Up @@ -150,7 +165,7 @@ def do(n, dry_run):

info_msg.header = msg.header
camera_options = {}
camera_options['name'] = "wide_angle_camera_front"
camera_options["name"] = "wide_angle_camera_front"
camera_options["use_for_training"] = True

info_msg.header = msg.header
Expand Down
1 change: 0 additions & 1 deletion wild_visual_navigation_ros/scripts/rotate_image.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
from cv_bridge import CvBridge, CvBridgeError



class ImageRotator:
def __init__(self):
self.bridge = CvBridge()
Expand Down
19 changes: 15 additions & 4 deletions wild_visual_navigation_ros/scripts/wild_visual_navigation_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,9 @@ def read_params(self):

# Select mode: # debug, online, extract_labels
self.use_debug_for_desired = rospy.get_param("~use_debug_for_desired") # Note: Unused parameter
self.use_binary_only = rospy.get_param("~use_binary_only") # Only extract binary labels, do not update traversability
self.use_binary_only = rospy.get_param(
"~use_binary_only"
) # Only extract binary labels, do not update traversability
self.mode = WVNMode.from_string(rospy.get_param("~mode", "debug"))
self.extraction_store_folder = rospy.get_param("~extraction_store_folder")

Expand Down Expand Up @@ -510,7 +512,12 @@ def query_tf(self, parent_frame: str, child_frame: str, stamp: Optional[rospy.Ti
res = self.tf_buffer.lookup_transform(parent_frame, child_frame, stamp)
trans = (res.transform.translation.x, res.transform.translation.y, res.transform.translation.z)
rot = np.array(
[res.transform.rotation.x, res.transform.rotation.y, res.transform.rotation.z, res.transform.rotation.w]
[
res.transform.rotation.x,
res.transform.rotation.y,
res.transform.rotation.z,
res.transform.rotation.w,
]
)
rot /= np.linalg.norm(rot)
return (trans, tuple(rot))
Expand Down Expand Up @@ -593,7 +600,11 @@ def robot_state_callback(self, state_msg, desired_twist_msg: TwistStamped):
desired_twist_tensor = rc.twist_stamped_to_torch(desired_twist_msg, device=self.device)

# Update traversability
traversability, traversability_var, is_untraversable = self.supervision_generator.update_velocity_tracking(
(
traversability,
traversability_var,
is_untraversable,
) = self.supervision_generator.update_velocity_tracking(
current_twist_tensor, desired_twist_tensor, velocities=["vx", "vy"]
)

Expand Down Expand Up @@ -706,7 +717,7 @@ def image_callback(self, image_msg: Image, info_msg: CameraInfo, camera_options:

# Add node to graph
added_new_node = self.traversability_estimator.add_mission_node(mission_node)

if not self.use_binary_only:
with SystemLevelContextGpuMonitor(self, "update_prediction"):
with SystemLevelContextTimer(self, "update_prediction"):
Expand Down

0 comments on commit 467149e

Please sign in to comment.