diff --git a/src/slam_wrapper.cpp b/src/slam_wrapper.cpp index a91dc9e..4a8bfbd 100644 --- a/src/slam_wrapper.cpp +++ b/src/slam_wrapper.cpp @@ -37,13 +37,16 @@ const std::vector right_command = { 0xFE, 0xFE, 0x0F, 0x3C, 0x0A, 0x40, 0x0A, 0x89, 0x03, 0xDE, 0x08, 0x43, 0x09, 0xA8, 0x07, 0xE1, 0x1E, 0xFA }; + const std::vector default_command = { + 0xFE, 0xFE, 0x0F, 0x3C, 0x07, 0xF7, 0x08, 0x18, 0x08, 0x0B, 0x08, 0x4B, 0x0A, 0x7D, 0x08, 0x0A, 0x1E, 0xFA + }; std::cout << "control_robotic_arm start" << std::endl; serial_port_->write(left_command); std::this_thread::sleep_for(std::chrono::seconds(3)); serial_port_->write(right_command); std::this_thread::sleep_for(std::chrono::seconds(3)); - serial_port_->write(init_command); + serial_port_->write(default_command); std::cout << "control_robotic_arm end" << std::endl; } @@ -60,9 +63,9 @@ std::cout << "move_to_i start" << std::endl; serial_port_->write(left_command); - std::this_thread::sleep_for(std::chrono::seconds(3)); + std::this_thread::sleep_for(std::chrono::seconds(6)); serial_port_->write(right_command); - std::this_thread::sleep_for(std::chrono::seconds(3)); + std::this_thread::sleep_for(std::chrono::seconds(9)); serial_port_->write(default_command); std::cout << "move_to_i end" << std::endl; }