Skip to content

Commit

Permalink
Skiddy pre-finals tweaks (#936)
Browse files Browse the repository at this point in the history
* traversability.cc - use waitForTransform()

* osgar/drivers/cortexpilot.py - hack, disable oscillate and limit turn to 15deg/sec

* disable statistics and save rosbag

* subt/script/run_skiddy.bash - parameters used for finals
  • Loading branch information
m3d authored Sep 25, 2021
1 parent f6e07e2 commit d249225
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 9 deletions.
4 changes: 3 additions & 1 deletion osgar/drivers/cortexpilot.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
RAMP_STEP = 0.1 # fractional number for speed in -1.0 .. 1.0

SOFT_SPEED_LIMIT = 1.0 # m/s ... software speed limit, abs() value
SOFT_ANGULAR_SPEED_LIMIT = math.radians(45) # rad/s
SOFT_ANGULAR_SPEED_LIMIT = math.radians(15) # rad/s


def sint32_diff(a, b):
Expand Down Expand Up @@ -310,12 +310,14 @@ def process_packet(self, packet):

def on_desired_speed(self, data):
self.desired_speed, self.desired_angular_speed = data[0] / 1000.0, math.radians(data[1] / 100.0)
"""
if abs(self.desired_speed) < 0.2 and abs(self.desired_angular_speed) > 0.2:
if self.speeds.__name__ != "oscilate":
self.speeds = self.oscilate()
else:
if self.speeds.__name__ == "oscilate":
self.speeds = self.plain_speeds()
"""
self.cmd_flags |= 0x02 # PWM ON

def run(self):
Expand Down
18 changes: 15 additions & 3 deletions subt/ros/proxy/traversability.cc
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,7 @@ std::optional<tf::StampedTransform> Traversability::GetTransform(
{
tf::StampedTransform pose;
tf::TransformException error("none");
for (int i = 0; i < 40; ++i)
/*for (int i = 0; i < 40; ++i)
{
try
{
Expand All @@ -271,8 +271,20 @@ std::optional<tf::StampedTransform> Traversability::GetTransform(
error = e;
ros::Duration(0.005).sleep();
}
}
ROS_ERROR("%s", error.what());
}*/

try
{
transform_listener_.waitForTransform(target_frame, source_frame, when, ros::Duration(0.2));
transform_listener_.lookupTransform(target_frame, source_frame, when, pose);
return pose;
}
catch (tf::TransformException& e)
{
error = e;
ros::Duration(0.005).sleep();
}
ROS_ERROR("MD-%s", error.what());
return {};
}

Expand Down
4 changes: 1 addition & 3 deletions subt/ros/robot/launch/skiddy.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
<?xml version="1.0"?>
<launch>
<param name="enable_statistics" value="true"/>

<!-- Announces position of the point tracked by tracking camera relative to the center of the robot. -->
<node pkg="tf" type="static_transform_publisher" name="tracked_point_tf" args="0.282 0 0.33 0 0 0 global odom 100" />
<!-- Announces the position of the center of the robot relative to the point tracked by tracking camera in Osgar.
Expand Down Expand Up @@ -89,6 +87,6 @@
<param name="output_pointcloud_channel" value="points"/>
</node>

<node name="record" pkg="rosbag" type="record" args="-a -o /tmp/skiddy"/>
<node name="record" pkg="rosbag" type="record" args="-a -o skiddy"/>

</launch>
4 changes: 2 additions & 2 deletions subt/script/run_skiddy.bash
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,6 @@ export PYTHONPATH=${PWD}:${PYTHONPATH}
export OMP_NUM_THREADS=1 # Make OpenCV eat fewer cpus.
python3 -m osgar.record config/skiddy-subt-serialloop.json &
pidcore=$!
python3 -m subt.main --use-old-record run config/skiddy-subt.json --side left --speed 0.4 --timeout 180 --wall-dist 1.0 --gap-size 1.0
python3 -m subt.main --use-old-record run config/skiddy-subt.json --side right --speed 0.4 --timeout 900 --wall-dist 0.6 --gap-size 0.6 --init-path "15.0,0"
#python3 -m osgar.go run config/skiddy-subt.json -s 0.3 -d -4 --timeout 30
kill "$pidcore"
kill "$pidcore"

0 comments on commit d249225

Please sign in to comment.