Skip to content

Commit

Permalink
rust: rros: remove all redundant comments
Browse files Browse the repository at this point in the history
There are many unnecessary comments in the code, remove them to standardize the code.

#15
  • Loading branch information
JiajunDu authored and Richardhongyu committed Dec 18, 2023
1 parent bf42e85 commit ad12a06
Show file tree
Hide file tree
Showing 41 changed files with 171 additions and 891 deletions.
125 changes: 32 additions & 93 deletions kernel/rros/clock.rs
Original file line number Diff line number Diff line change
@@ -1,7 +1,3 @@
// #![feature(allocator_api)]
// #![allow(warnings, unused)]
// #![feature(stmt_expr_attributes)]

#![allow(warnings, unused)]
#![feature(stmt_expr_attributes)]
use crate::{
Expand All @@ -15,7 +11,9 @@ use crate::{
tick,
timeout::RROS_INFINITE,
};

use alloc::rc::Rc;

use core::{
borrow::{Borrow, BorrowMut},
cell::{RefCell, UnsafeCell},
Expand All @@ -24,6 +22,7 @@ use core::{
mem::{align_of, size_of},
todo,
};

use kernel::{
bindings, c_types, cpumask, double_linked_list::*, file_operations::{FileOperations, FileOpener}, ktime::*,
percpu, prelude::*, premmpt, spinlock_init, str::CStr, sync::Lock, sync::SpinLock, sysfs,
Expand All @@ -37,11 +36,12 @@ use kernel::{

static mut CLOCKLIST_LOCK: SpinLock<i32> = unsafe { SpinLock::new(1) };

const CONFIG_RROS_LATENCY_USER: KtimeT = 0; //这里先定义为常量,后面应该从/dev/rros中读取
// Define it as a constant here first, and then read it from /dev/rros.
const CONFIG_RROS_LATENCY_USER: KtimeT = 0;
const CONFIG_RROS_LATENCY_KERNEL: KtimeT = 0;
const CONFIG_RROS_LATENCY_IRQ: KtimeT = 0;

// there should be 8
// There should be 8.
pub const CONFIG_RROS_NR_CLOCKS: usize = 16;

#[derive(Default)]
Expand Down Expand Up @@ -86,11 +86,10 @@ impl RrosClockGravity {
}
}

//定义时钟操作
pub struct RrosClockOps {
read: Option<fn(&RrosClock) -> KtimeT>,
readcycles: Option<fn(&RrosClock) -> u64>,
set: Option<fn(&mut RrosClock, KtimeT) -> i32>, //int
set: Option<fn(&mut RrosClock, KtimeT) -> i32>,
programlocalshot: Option<fn(&RrosClock)>,
programremoteshot: Option<fn(&RrosClock, *mut RrosRq)>,
setgravity: Option<fn(&mut RrosClock, RrosClockGravity)>,
Expand All @@ -102,7 +101,7 @@ impl RrosClockOps {
pub fn new(
read: Option<fn(&RrosClock) -> KtimeT>,
readcycles: Option<fn(&RrosClock) -> u64>,
set: Option<fn(&mut RrosClock, KtimeT) -> i32>, //int
set: Option<fn(&mut RrosClock, KtimeT) -> i32>,
programlocalshot: Option<fn(&RrosClock)>,
programremoteshot: Option<fn(&RrosClock, *mut RrosRq)>,
setgravity: Option<fn(&mut RrosClock, RrosClockGravity)>,
Expand Down Expand Up @@ -136,9 +135,8 @@ pub struct RrosClock {
dispose: Option<fn(&mut RrosClock)>,
#[cfg(CONFIG_SMP)]
pub affinity: Option<cpumask::CpumaskT>,
} //____cacheline_aligned
}

//RrosClock主方法
impl RrosClock {
pub fn new(
resolution: KtimeT,
Expand Down Expand Up @@ -171,14 +169,14 @@ impl RrosClock {
}
}
pub fn read(&self) -> KtimeT {
//错误处理
// Error handling.
if self.ops.read.is_some() {
return self.ops.read.unwrap()(&self);
}
return 0;
}
pub fn read_cycles(&self) -> u64 {
//错误处理
// Error handling.
if self.ops.readcycles.is_some() {
return self.ops.readcycles.unwrap()(&self);
}
Expand All @@ -188,7 +186,8 @@ impl RrosClock {
if self.ops.set.is_some() {
self.ops.set.unwrap()(self, time);
} else {
return Err(kernel::Error::EFAULT); //阻止函数为null情况的执行
// Prevent the execution of the function if it is null.
return Err(kernel::Error::EFAULT);
}
Ok(0)
}
Expand Down Expand Up @@ -218,7 +217,7 @@ impl RrosClock {
}
}
pub fn get_timerdata_addr(&self) -> *mut RrosTimerbase {
//错误处理
// Error handling.
return self.timerdata as *mut RrosTimerbase;
}

Expand All @@ -243,7 +242,6 @@ impl RrosClock {
}
}

//测试通过
pub fn adjust_timer(
clock: &RrosClock,
timer: Arc<SpinLock<RrosTimer>>,
Expand Down Expand Up @@ -295,12 +293,11 @@ pub fn adjust_timer(
rros_enqueue_timer(timer.clone(), tq);
}

//简单测过
//调整当前clock各个CPU tmb中List中的所有timer
pub fn rros_adjust_timers(clock: &mut RrosClock, delta: KtimeT) {
//raw_spin_lock_irqsave(&tmb->lock, flags);
// Adjust all timers in the List in each CPU tmb of the current clock.
// raw_spin_lock_irqsave(&tmb->lock, flags);
let cpu = 0;
//for_each_online_cpu(cpu) {
// for_each_online_cpu(cpu) {
let rq = rros_cpu_rq(cpu);
let tmb = rros_percpu_timers(clock, cpu);
let tq = unsafe { &mut (*tmb).q };
Expand All @@ -322,7 +319,6 @@ pub fn rros_adjust_timers(clock: &mut RrosClock, delta: KtimeT) {
//}
}

//测试通过
pub fn rros_stop_timers(clock: &RrosClock) {
let cpu = 0;
let mut tmb = rros_percpu_timers(&clock, cpu);
Expand All @@ -336,30 +332,9 @@ pub fn rros_stop_timers(clock: &RrosClock) {
}
}

/*
void inband_clock_was_set(void)
{
struct rros_clock *clock;
if (!rros_is_enabled())
return;
mutex_lock(&clocklist_lock);
list_for_each_entry(clock, &clock_list, next) {
if (clock->ops.adjust)
clock->ops.adjust(clock);
}
mutex_unlock(&clocklist_lock);
}
*/

//打印clock的初始化log
// Print the initialization log of the clock.
fn rros_clock_log() {}

/*mono时钟操作 */

fn read_mono_clock(clock: &RrosClock) -> KtimeT {
timekeeping::ktime_get_mono_fast_ns()
}
Expand All @@ -369,13 +344,15 @@ fn read_mono_clock_cycles(clock: &RrosClock) -> u64 {
}

fn set_mono_clock(clock: &mut RrosClock, time: KtimeT) -> i32 {
//mono无法设置,后面应该为错误类型
// mono cannot be set, the following should be an error type.
0
}

fn adjust_mono_clock(clock: &mut RrosClock) {}

/*realtime时钟操作 */
/**
* The following functions are the realtime clock operations.
*/

fn read_realtime_clock(clock: &RrosClock) -> KtimeT {
timekeeping::ktime_get_real_fast_ns()
Expand All @@ -397,7 +374,9 @@ fn adjust_realtime_clock(clock: &mut RrosClock) {
// rros_adjust_timers(clock, clock.offset - old_offset)
}

/*通用clock操作 */
/**
* The following functions are universal clock operations.
*/

fn get_default_gravity() -> RrosClockGravity {
RrosClockGravity {
Expand All @@ -417,9 +396,9 @@ fn reset_coreclk_gravity(clock: &mut RrosClock) {
set_coreclk_gravity(clock, get_default_gravity());
}

//两个全局变量MONO和REALTIME
static RROS_MONO_CLOCK_NAME: &CStr =
unsafe { CStr::from_bytes_with_nul_unchecked("RROS_CLOCK_MONOTONIC_DEV\0".as_bytes()) };

pub static mut RROS_MONO_CLOCK: RrosClock = RrosClock {
name: RROS_MONO_CLOCK_NAME,
resolution: 1,
Expand Down Expand Up @@ -454,6 +433,7 @@ pub static mut RROS_MONO_CLOCK: RrosClock = RrosClock {

static RROS_REALTIME_CLOCK_NAME: &CStr =
unsafe { CStr::from_bytes_with_nul_unchecked("RROS_CLOCK_REALTIME_DEV\0".as_bytes()) };

pub static mut RROS_REALTIME_CLOCK: RrosClock = RrosClock {
name: RROS_REALTIME_CLOCK_NAME,
resolution: 1,
Expand Down Expand Up @@ -545,30 +525,6 @@ impl FileOperations for ClockOps {

pub fn clock_factory_dispose(ele: factory::RrosElement) {}

/*
void rros_core_tick(struct clock_event_device *dummy) /* hard irqs off */
{
struct rros_rq *this_rq = this_rros_rq();
struct rros_timerbase *tmb;
if (RROS_WARN_ON_ONCE(CORE, !is_rros_cpu(rros_rq_cpu(this_rq))))
return;
tmb = rros_this_cpu_timers(&rros_mono_clock);
do_clock_tick(&rros_mono_clock, tmb);
/*
* If an RROS thread was preempted by this clock event, any
* transition to the in-band context will cause a pending
* in-band tick to be propagated by rros_schedule() called from
* rros_exit_irq(), so we may have to propagate the in-band
* tick immediately only if the in-band context was preempted.
*/
if ((this_rq->local_flags & RQ_TPROXY) && (this_rq->curr->state & T_ROOT))
rros_notify_proxy_tick(this_rq);
}
*/

fn timer_needs_enqueuing(timer: *mut RrosTimer) -> bool {
unsafe {
return ((*timer).get_status()
Expand All @@ -580,7 +536,7 @@ fn timer_needs_enqueuing(timer: *mut RrosTimer) -> bool {
}
}

//rq相关未测试,其余测试通过
// `rq` related tests haven't been tested, other tests passed.
pub fn do_clock_tick(clock: &mut RrosClock, tmb: *mut RrosTimerbase) {
let rq = this_rros_rq();
// #[cfg(CONFIG_RROS_DEBUG_CORE)]
Expand Down Expand Up @@ -670,7 +626,7 @@ impl clockchips::CoreTick for RrosCoreTick {
let rq_has_tproxy = ((*this_rq).local_flags & RQ_TPROXY != 0x0);
let assd = (*(*this_rq).get_curr().locked_data().get()).state;
let curr_state_is_t_root = (assd & (T_ROOT as u32) != 0x0);
//这个if进不去有问题!!
// This `if` won't enter, so there is a problem.
// let a = ((*this_rq).local_flags & RQ_TPROXY != 0x0);
// if rq_has_tproxy {
// pr_debug!("in rros_core_tick");
Expand Down Expand Up @@ -701,7 +657,6 @@ impl clockchips::CoreTick for RrosCoreTick {
}
}

//初始化时钟
fn init_clock(clock: *mut RrosClock, master: *mut RrosClock) -> Result<usize> {
// unsafe{
// if (*clock).element.is_none(){
Expand All @@ -726,11 +681,10 @@ fn init_clock(clock: *mut RrosClock, master: *mut RrosClock) -> Result<usize> {
Ok(0)
}

//初始化时钟slave
fn rros_init_slave_clock(clock: &mut RrosClock, master: &mut RrosClock) -> Result<usize> {
premmpt::running_inband()?;

//这里为什么会报错,timer就可以跑?为什么卧槽
// TODO: Check if there is a problem here, even if the timer can run.
// #[cfg(CONFIG_SMP)]
// clock.affinity = master.affinity;

Expand All @@ -740,13 +694,13 @@ fn rros_init_slave_clock(clock: &mut RrosClock, master: &mut RrosClock) -> Resul
Ok(0)
}

//rros初始化时钟
fn rros_init_clock(clock: &mut RrosClock, affinity: &cpumask::CpumaskT) -> Result<usize> {
premmpt::running_inband()?;
// 8 byte alignment
let tmb = percpu::alloc_per_cpu(
size_of::<RrosTimerbase>() as usize,
align_of::<RrosTimerbase>() as usize,
) as *mut RrosTimerbase; //8字节对齐
) as *mut RrosTimerbase;
if tmb == 0 as *mut RrosTimerbase {
return Err(kernel::Error::ENOMEM);
}
Expand All @@ -767,7 +721,6 @@ fn rros_init_clock(clock: &mut RrosClock, affinity: &cpumask::CpumaskT) -> Resul
Ok(0)
}

//时钟系统初始化
pub fn rros_clock_init() -> Result<usize> {
let pinned = unsafe { Pin::new_unchecked(&mut CLOCKLIST_LOCK) };
spinlock_init!(pinned, "CLOCKLIST_LOCK");
Expand Down Expand Up @@ -798,17 +751,3 @@ pub fn rros_read_clock(clock: &RrosClock) -> KtimeT {
fn rros_ktime_monotonic() -> KtimeT {
timekeeping::ktime_get_mono_fast_ns()
}

// static inline ktime_t rros_read_clock(struct rros_clock *clock)
// {
// /*
// * In many occasions on the fast path, rros_read_clock() is
// * explicitly called with &rros_mono_clock which resolves as
// * a constant. Skip the clock trampoline handler, branching
// * immediately to the final code for such clock.
// */
// if (clock == &rros_mono_clock)
// return rros_ktime_monotonic();

// return clock->ops.read(clock);
// }
7 changes: 1 addition & 6 deletions kernel/rros/clock_test.rs
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
//clock.rs测试文件
//用于测试clock.rs里的函数正确&性
use crate::{clock::*, timer::*};

use kernel::{ktime::*, prelude::*, spinlock_init, sync::SpinLock};

//测试通过
#[allow(dead_code)]
pub fn test_do_clock_tick() -> Result<usize> {
pr_debug!("~~~test_do_clock_tick begin~~~");
Expand All @@ -30,7 +28,6 @@ pub fn test_do_clock_tick() -> Result<usize> {
Ok(0)
}

//测试通过
#[allow(dead_code)]
pub fn test_adjust_timer() -> Result<usize> {
pr_debug!("~~~test_adjust_timer begin~~~");
Expand All @@ -57,7 +54,6 @@ pub fn test_adjust_timer() -> Result<usize> {
Ok(0)
}

//测试通过
#[allow(dead_code)]
pub fn test_rros_adjust_timers() -> Result<usize> {
pr_debug!("~~~test_rros_adjust_timers begin~~~");
Expand Down Expand Up @@ -103,7 +99,6 @@ pub fn test_rros_adjust_timers() -> Result<usize> {
Ok(0)
}

//测试通过
#[allow(dead_code)]
pub fn test_rros_stop_timers() -> Result<usize> {
pr_debug!("~~~test_rros_stop_timers begin~~~");
Expand Down
2 changes: 1 addition & 1 deletion kernel/rros/control.rs
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ fn control_ioctl(file: &File, cmd: &mut IoctlCommand) -> Result<i32> {
info.abi_base = RROS_ABI_BASE;
info.abi_current = RROS_ABI_LEVEL;
// in arch/arm64/include/asm/rros/fptest.h
// TODO There should be a function rros_detect_fpu() related to the arm64 architecture, the result of the function is 0.
// TODO: There should be a function rros_detect_fpu() related to the arm64 architecture, the result of the function is 0.
info.fpu_features = 0;
unsafe {
pr_debug!(
Expand Down
Loading

0 comments on commit ad12a06

Please sign in to comment.