use structopt::StructOpt;
use tracing::{debug, warn};
use urdf_viz::{app::*, WebServer};
const DEFAULT_WEB_SERVER_PORT: u16 = 7777;
#[tokio::main]
async fn main() -> urdf_viz::Result<()> {
tracing_subscriber::fmt::init();
let opt = Opt::from_args();
debug!(?opt);
let package_path = opt.create_package_path_map()?;
let urdf_robot = urdf_viz::utils::RobotModel::new(
&opt.input_urdf_or_xacro,
package_path,
&opt.xacro_arguments,
)?;
let ik_constraints = opt.create_ik_constraints();
let mut app = UrdfViewerApp::new(
urdf_robot,
opt.end_link_names,
opt.is_collision,
opt.disable_texture,
#[cfg(feature = "assimp")]
opt.disable_assimp,
#[cfg(not(feature = "assimp"))]
true,
(
opt.back_ground_color_r,
opt.back_ground_color_g,
opt.back_ground_color_b,
),
(opt.tile_color1_r, opt.tile_color1_g, opt.tile_color1_b),
(opt.tile_color2_r, opt.tile_color2_g, opt.tile_color2_b),
opt.ground_height,
opt.hide_menu,
opt.axis_scale,
opt.move_base_diff_unit,
opt.move_joint_diff_unit,
)?;
app.set_ik_constraints(ik_constraints);
app.init();
match WebServer::new(
opt.web_server_port.unwrap_or(DEFAULT_WEB_SERVER_PORT),
app.handle(),
)
.bind()
{
Ok(server) => {
tokio::spawn(async move { server.await.unwrap() });
}
Err(e) => {
if opt.web_server_port.is_none() {
warn!("failed to start web server with default port: {e}");
} else {
return Err(e);
}
}
}
app.run();
Ok(())
}