auto
This commit is contained in:
parent
9cce7f25a0
commit
ab26100687
6
a.sh
Executable file
6
a.sh
Executable file
@ -0,0 +1,6 @@
|
|||||||
|
sudo ip link set can0 down
|
||||||
|
sudo ip link set can0 up type can bitrate 500000
|
||||||
|
sudo chmod 666 /dev/ttyUSB5
|
||||||
|
sudo chmod 666 /dev/ttyUSB5
|
||||||
|
source install/setup.bash
|
||||||
|
#sudo insmod drivers/usb/serial/pl2303.ko
|
||||||
@ -95,11 +95,11 @@ void setupTimers(rclcpp::Node::SharedPtr node)
|
|||||||
mcu_cmd.setBrake(msg.brake);
|
mcu_cmd.setBrake(msg.brake);
|
||||||
mcu_cmd.pack();
|
mcu_cmd.pack();
|
||||||
|
|
||||||
vcu1_cmd.setLeftLight(msg.left_light);
|
|
||||||
vcu1_cmd.setNightLightPercent(msg.night_light);
|
|
||||||
|
|
||||||
canctl.sendFrame(mcu_cmd.toFrame());
|
canctl.sendFrame(mcu_cmd.toFrame());
|
||||||
canctl.sendFrame(vcu1_cmd.toFrame()); });
|
|
||||||
|
});
|
||||||
|
|
||||||
// EPS 控制,20Hz
|
// EPS 控制,20Hz
|
||||||
static rclcpp::TimerBase::SharedPtr timer_eps = node->create_wall_timer(
|
static rclcpp::TimerBase::SharedPtr timer_eps = node->create_wall_timer(
|
||||||
@ -114,7 +114,8 @@ void setupTimers(rclcpp::Node::SharedPtr node)
|
|||||||
eps_cmd.setControlMode(0x20);
|
eps_cmd.setControlMode(0x20);
|
||||||
eps_cmd.pack();
|
eps_cmd.pack();
|
||||||
|
|
||||||
canctl.sendFrame(eps_cmd.toFrame()); });
|
canctl.sendFrame(eps_cmd.toFrame());
|
||||||
|
});
|
||||||
|
|
||||||
// VCU2 控制,10Hz
|
// VCU2 控制,10Hz
|
||||||
static rclcpp::TimerBase::SharedPtr timer_vcu = node->create_wall_timer(
|
static rclcpp::TimerBase::SharedPtr timer_vcu = node->create_wall_timer(
|
||||||
@ -123,6 +124,9 @@ void setupTimers(rclcpp::Node::SharedPtr node)
|
|||||||
mc::msg::McCtrl msg;
|
mc::msg::McCtrl msg;
|
||||||
if (!control_cache.get(msg)) return;
|
if (!control_cache.get(msg)) return;
|
||||||
|
|
||||||
|
vcu1_cmd.setLeftLight(msg.left_light);
|
||||||
|
vcu1_cmd.setNightLightPercent(msg.night_light);
|
||||||
|
|
||||||
vcu2_cmd.setBrakeLight(msg.brake_light);
|
vcu2_cmd.setBrakeLight(msg.brake_light);
|
||||||
vcu2_cmd.setDustShake(msg.dust_shake);
|
vcu2_cmd.setDustShake(msg.dust_shake);
|
||||||
vcu2_cmd.setEdgeBrushLift(msg.edge_brush_lift);
|
vcu2_cmd.setEdgeBrushLift(msg.edge_brush_lift);
|
||||||
@ -133,7 +137,10 @@ void setupTimers(rclcpp::Node::SharedPtr node)
|
|||||||
vcu2_cmd.setSpray(msg.spray);
|
vcu2_cmd.setSpray(msg.spray);
|
||||||
vcu2_cmd.setVacuum(msg.vacuum);
|
vcu2_cmd.setVacuum(msg.vacuum);
|
||||||
|
|
||||||
canctl.sendFrame(vcu2_cmd.toFrame()); });
|
//canctl.sendFrame(vcu1_cmd.toFrame());
|
||||||
|
|
||||||
|
canctl.sendFrame(vcu2_cmd.toFrame());
|
||||||
|
});
|
||||||
|
|
||||||
// 刷子控制,3.3Hz
|
// 刷子控制,3.3Hz
|
||||||
static rclcpp::TimerBase::SharedPtr timer_brush = node->create_wall_timer(
|
static rclcpp::TimerBase::SharedPtr timer_brush = node->create_wall_timer(
|
||||||
@ -149,7 +156,8 @@ void setupTimers(rclcpp::Node::SharedPtr node)
|
|||||||
edge_brush_cmd.setBrushPwm(msg.edge_brush_pwm);
|
edge_brush_cmd.setBrushPwm(msg.edge_brush_pwm);
|
||||||
|
|
||||||
canctl.sendFrame(main_brush_cmd.toFrame());
|
canctl.sendFrame(main_brush_cmd.toFrame());
|
||||||
canctl.sendFrame(edge_brush_cmd.toFrame()); });
|
canctl.sendFrame(edge_brush_cmd.toFrame());
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
void VCUWakeUp()
|
void VCUWakeUp()
|
||||||
|
|||||||
@ -127,7 +127,7 @@ private:
|
|||||||
msg.vacuum = true;
|
msg.vacuum = true;
|
||||||
msg.spray = true;
|
msg.spray = true;
|
||||||
msg.mud_flap = true;
|
msg.mud_flap = true;
|
||||||
msg.dust_shake = true;
|
msg.dust_shake = false;
|
||||||
msg.main_brush_spin = true;
|
msg.main_brush_spin = true;
|
||||||
msg.edge_brush_spin = true;
|
msg.edge_brush_spin = true;
|
||||||
msg.main_brush_pwm = 100;
|
msg.main_brush_pwm = 100;
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user