Skip to content

Commit

Permalink
Pre-commit changes
Browse files Browse the repository at this point in the history
  • Loading branch information
b1n-ch1kn committed Sep 15, 2024
1 parent 4ee68fa commit 5694283
Show file tree
Hide file tree
Showing 10 changed files with 51 additions and 22 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def cmd_callback(self, twist_msg: Twist):
steering = 0.0
else:
radius = vel / twist_msg.angular.z
atan(self.wheelbase / radius) * (180 / pi) * self.Kp ## MAKE THIS A PARAM
atan(self.wheelbase / radius) * (180 / pi) * self.Kp ## MAKE THIS A PARAM

msg = AckermannDriveStamped()
# make time for msg id
Expand Down
5 changes: 3 additions & 2 deletions src/hardware/canbus/src/component_canbus_translator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,11 @@ void CANTranslator::canmsg_timer() {
for (int i = 0; i < 4; i++) {
av_velocity += wheel_speeds_[i];
}
av_velocity = av_velocity / 4; // maybe get a vector of x,y here?
av_velocity = av_velocity / 4; // maybe get a vector of x,y here?

// update twist msg with new velocity
geometry_msgs::msg::TwistWithCovarianceStamped::UniquePtr twist_msg(new geometry_msgs::msg::TwistWithCovarianceStamped());
geometry_msgs::msg::TwistWithCovarianceStamped::UniquePtr twist_msg(
new geometry_msgs::msg::TwistWithCovarianceStamped());
twist_msg->header.stamp = this->now();
twist_msg->header.frame_id = ros_base_frame_;
twist_msg->twist.twist.linear.x = av_velocity;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ class SteeringActuator : public rclcpp::Node, public CanInterface {
// time to reset node if no state received
std::chrono::time_point<std::chrono::system_clock> last_state_time = std::chrono::system_clock::now();

void update_parameters(const rcl_interfaces::msg::ParameterEvent& event);
void update_parameters(const rcl_interfaces::msg::ParameterEvent &event);
void configure_c5e();
void c5e_state_request_callback();
void as_state_callback(const driverless_msgs::msg::State::SharedPtr msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

namespace steering_actuator {

void SteeringActuator::update_parameters(const rcl_interfaces::msg::ParameterEvent& event) {
void SteeringActuator::update_parameters(const rcl_interfaces::msg::ParameterEvent &event) {
(void)event;

current_velocity_ = this->get_parameter("velocity").as_int();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,10 +70,12 @@ def odometry_callback(self, msg: Odometry):
local_odom.pose.pose.orientation = orientation(0, 0, relative_heading)
local_odom.twist = msg.twist
# Adjust the linear velocity to be relative to the initial heading
local_odom.twist.twist.linear.x = -(msg.twist.twist.linear.x * cos(relative_heading) + msg.twist.twist.linear.y * sin(
relative_heading))
local_odom.twist.twist.linear.y = -msg.twist.twist.linear.x * sin(relative_heading) + msg.twist.twist.linear.y * cos(
relative_heading)
local_odom.twist.twist.linear.x = -(
msg.twist.twist.linear.x * cos(relative_heading) + msg.twist.twist.linear.y * sin(relative_heading)
)
local_odom.twist.twist.linear.y = -msg.twist.twist.linear.x * sin(
relative_heading
) + msg.twist.twist.linear.y * cos(relative_heading)

self.publisher.publish(local_odom)

Expand Down
4 changes: 3 additions & 1 deletion src/navigation/planners/planners/node_ft_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,9 @@ def __init__(self):

self.path_planner = PathPlanner(**self.get_planner_cfg())

self.get_logger().info(f"---Ordered path planner node initalised with {self.topic_name}, {self.target_frame}---")
self.get_logger().info(
f"---Ordered path planner node initalised with {self.topic_name}, {self.target_frame}---"
)

def get_planner_cfg(self):
self.declare_parameter("mission", MissionTypes.trackdrive)
Expand Down
10 changes: 6 additions & 4 deletions src/operations/mission_controller/launch/ebs_test.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,11 @@ def generate_launch_description():
get_package_share_path("planners") / "config" / "ft_planner.yaml",
],
ros_arguments=[
"-p", "topic_name:=lidar/cone_detection",
"-p", "target_frame:=base_footprint",
]
"-p",
"topic_name:=lidar/cone_detection",
"-p",
"target_frame:=base_footprint",
],
),
# guidance/control
IncludeLaunchDescription(
Expand All @@ -42,7 +44,7 @@ def generate_launch_description():
Node(
package="controllers",
executable="vel_to_ackermann_node",
parameters=[{"Kp": 2.0}] # specific for EBS test
parameters=[{"Kp": 2.0}], # specific for EBS test
),
]
)
10 changes: 6 additions & 4 deletions src/operations/mission_controller/launch/trackdrive.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,11 @@ def generate_launch_description():
get_package_share_path("planners") / "config" / "ft_planner.yaml",
],
ros_arguments=[
"-p", "topic_name:=slam/global_map",
"-p", "target_frame:=track",
]
"-p",
"topic_name:=slam/global_map",
"-p",
"target_frame:=track",
],
),
# guidance/control
IncludeLaunchDescription(
Expand All @@ -49,7 +51,7 @@ def generate_launch_description():
Node(
package="controllers",
executable="vel_to_ackermann_node",
parameters=[{"Kp": 4.0}], # specific for Trackdrive
parameters=[{"Kp": 4.0}], # specific for Trackdrive
),
]
)
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,17 @@ def __init__(self):

self.mission_started = True

command = ["stdbuf", "-o", "L", "ros2", "param", "set", "velocity_controller_node", "min_time_to_max_accel_sec", "2.0"]
command = [
"stdbuf",
"-o",
"L",
"ros2",
"param",
"set",
"velocity_controller_node",
"min_time_to_max_accel_sec",
"2.0",
]
self.get_logger().info(f"Running Command: {' '.join(command)}")
cmd = Popen(command)
command = ["stdbuf", "-o", "L", "ros2", "param", "set", "steering_actuator_node", "max_position", "2000"]
Expand All @@ -71,7 +81,17 @@ def state_callback(self, msg: State):
and self.odom_received
):

command = ["stdbuf", "-o", "L", "ros2", "param", "set", "velocity_controller_node", "min_time_to_max_accel_sec", "2.0"]
command = [
"stdbuf",
"-o",
"L",
"ros2",
"param",
"set",
"velocity_controller_node",
"min_time_to_max_accel_sec",
"2.0",
]
self.get_logger().info(f"Running Command: {' '.join(command)}")
self.process = Popen(command)
command = ["stdbuf", "-o", "L", "ros2", "param", "set", "steering_actuator_node", "max_position", "2000"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ def timer_callback(self):
if track_to_base.transform.translation.x < 2:
self.last_x = track_to_base.transform.translation.x
return

# we have left the box
self.get_logger().info(f"Crossed start line in {time.time() - self.last_lap_time:.2f}s")

Expand All @@ -162,7 +162,7 @@ def timer_callback(self):
self.last_lap_time = time.time()

self.laps += 1
self.lap_trig_pub.publish(UInt8(data=self.laps-1))
self.lap_trig_pub.publish(UInt8(data=self.laps - 1))
self.get_logger().info(f"Lap {self.laps} completed")

# we have finished lap "1"
Expand Down

0 comments on commit 5694283

Please sign in to comment.