pub struct CoCube { /* private fields */ }Implementations§
Source§impl CoCube
impl CoCube
Sourcepub fn new(
robot_id: u32,
gateway: &str,
local_ip: &str,
ip_prefix: u32,
udp_port: u16,
) -> Result<Self>
pub fn new( robot_id: u32, gateway: &str, local_ip: &str, ip_prefix: u32, udp_port: u16, ) -> Result<Self>
Examples found in repository?
examples/main.rs (lines 7-13)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}Sourcepub fn get_position(&self) -> [i32; 3]
pub fn get_position(&self) -> [i32; 3]
Examples found in repository?
examples/main.rs (line 16)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}pub fn set_tft_backlight(&self, flag: u8)
pub fn draw_aruco_marker_on_tft(&self, id: u8)
Sourcepub fn move_robot(&self, direction: &str, speed: u8)
pub fn move_robot(&self, direction: &str, speed: u8)
Examples found in repository?
examples/main.rs (line 21)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}Sourcepub fn rotate_robot(&self, direction: &str, speed: u8)
pub fn rotate_robot(&self, direction: &str, speed: u8)
Examples found in repository?
examples/main.rs (line 26)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}pub fn move_millisecs( &self, direction: &str, speed: u8, duration: u64, ) -> Option<String>
pub fn rotate_millisecs( &self, direction: &str, speed: u8, duration: u64, ) -> Option<String>
pub fn move_by_steps( &self, direction: &str, speed: u8, step: u16, ) -> Option<String>
pub fn rotate_by_degree( &self, direction: &str, speed: u8, degree: u16, ) -> Option<String>
pub fn set_wheel_speed(&self, left: u8, right: u8)
Sourcepub fn wheels_stop(&self)
pub fn wheels_stop(&self)
Examples found in repository?
examples/main.rs (line 23)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}pub fn wheels_break(&self)
pub fn rotate_to_angle(&self, angle: i16, speed: u8)
pub fn rotate_to_target(&self, x: i32, y: i32, speed: u8)
pub fn move_to(&self, x: i32, y: i32, speed: u8)
pub fn move_to_target(&self, x: i32, y: i32, speed: u8)
pub fn power_on_module(&self)
pub fn power_off_module(&self)
pub fn gripper_open(&self)
pub fn gripper_close(&self)
pub fn gripper_degree(&self, degree: i8)
pub fn attach_neo_pixel(&self)
pub fn set_all_neo_pixels_color(&self, r: u8, g: u8, b: u8)
pub fn clear_neo_pixels(&self)
Sourcepub fn mb_display(&self, code: u32) -> Option<String>
pub fn mb_display(&self, code: u32) -> Option<String>
Examples found in repository?
examples/main.rs (line 55)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}pub fn mb_display_off(&self) -> Option<String>
Sourcepub fn set_display_color(&self, r: u8, g: u8, b: u8)
pub fn set_display_color(&self, r: u8, g: u8, b: u8)
Examples found in repository?
examples/main.rs (line 54)
5fn main() -> Result<(), Box<dyn std::error::Error>> {
6 // 初始化CoCube实例
7 let agent = CoCube::new(
8 1,
9 "192.168.31.1",
10 "192.168.31.31",
11 1,
12 6000
13 )?;
14
15 // 获取并打印位置信息
16 let pos = agent.get_position();
17 println!("Current position: x={:.2}, y={:.2}, yaw={:.2}rad", pos[0], pos[1], pos[2]);
18
19 // 基础运动控制示例
20 println!("Moving forward...");
21 agent.move_robot("forward", 40);
22 thread::sleep(Duration::from_secs(2));
23 agent.wheels_stop();
24
25 println!("Rotating left...");
26 agent.rotate_robot("left", 30);
27 thread::sleep(Duration::from_secs(2));
28 agent.wheels_stop();
29
30 // 目标点导航示例
31 let target_x = 200.0;
32 let target_y = 200.0;
33 println!("Moving to target ({}, {})", target_x, target_y);
34 // agent.move_to_target(target_x, target_y, 50);
35
36 // 等待到达目标点
37 // loop {
38 // let curr_pos = agent.get_position();
39 // let dx = curr_pos[0] - target_x;
40 // let dy = curr_pos[1] - target_y;
41 // let distance = (dx.powi(2) + dy.powi(2)).sqrt();
42
43 // println!("Current position: ({:.1}, {:.1}), Distance: {:.1} points",
44 // curr_pos[0], curr_pos[1], distance);
45
46 // if distance < 10.0 {
47 // println!("Reached target!");
48 // break;
49 // }
50 // thread::sleep(Duration::from_millis(100));
51 // }
52
53 // 显示控制示例
54 agent.set_display_color(0, 255, 0); // 设置绿色
55 if let Some(_) = agent.mb_display(33554431) {
56 // 成功处理显示命令
57 }
58
59 Ok(())
60}Trait Implementations§
Auto Trait Implementations§
impl Freeze for CoCube
impl RefUnwindSafe for CoCube
impl Send for CoCube
impl Sync for CoCube
impl Unpin for CoCube
impl UnwindSafe for CoCube
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more