diff --git a/CMakeLists.txt b/CMakeLists.txt index 6ba1f887e94126089d27ece8e16535fb8aa81161..3e04fbb4f42a75802d8fc4f1eea716e64ff4d39f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,25 +71,28 @@ include_directories(${catkin_INCLUDE_DIRS}) # add custom controller as library add_library(${PROJECT_NAME}_controllers_lib src/joint_position_controller.cpp) -add_library(linkstate src/linkstate.pb.cc src/linkstate.pb.h) +add_library(linkstate src/messages/linkstate.pb.cc src/messages/linkstate.pb.h) +add_library(dataconfig src/messages/dataconfig.pb.cc src/messages/dataconfig.pb.h) +add_library(robotconfig src/messages/robotconfig.pb.cc src/messages/robotconfig.pb.h) # Specify libraries to link a library or executable target against target_link_libraries(${PROJECT_NAME}_controllers_lib ${catkin_LIBRARIES}) add_executable(robot_control_node src/robot_control_node.cpp) -add_executable(box_publisher_node src/box_publisher.cpp) add_executable(robot_state_initializer_node src/robot_state_initializer.cpp) add_executable(SafetyAwarePlanner src/SafetyAwarePlanner.cpp src/SafetyEnvironmentCreator.cpp) -add_executable(SampleConstraintPlanner src/SampleConstraintPlanner.cpp) +add_executable(SampleConstraintPlanner src/samples/SampleConstraintPlanner.cpp) +add_executable(SampleTimedCartesianPlanner src/samples/SampleTimedCartesianPlanner.cpp) add_executable(RobotStateProvider src/RobotStateProvider.cpp src/mem_persistence.cpp) add_executable(TimedCartesianPlanner src/TimedCartesianPlanner.cpp) add_executable(MqttToRosNode src/MqttToRosNode.cpp) +add_executable(MqttRosConnectionTestNode src/MqttRosConnectionTestNode.cpp) target_link_libraries(robot_control_node ${catkin_LIBRARIES} boost_filesystem ${JSONCPP_LIBRARIES}) -target_link_libraries(box_publisher_node ${catkin_LIBRARIES}) target_link_libraries(robot_state_initializer_node ${catkin_LIBRARIES}) target_link_libraries(SafetyAwarePlanner ${catkin_LIBRARIES}) -target_link_libraries(SampleConstraintPlanner ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +target_link_libraries(SampleConstraintPlanner ${catkin_LIBRARIES}) +target_link_libraries(SampleTimedCartesianPlanner ${catkin_LIBRARIES}) target_link_libraries(RobotStateProvider LINK_PUBLIC ${catkin_LIBRARIES} ${PahoMqtt3c} @@ -105,5 +108,17 @@ target_link_libraries(MqttToRosNode LINK_PUBLIC ${PahoMqtt3cs} ${PahoMqtt3a} ${PahoMqtt3as} - ${PahoMqttCpp}) + ${PahoMqttCpp} + ${Protobuf_LIBRARIES} + dataconfig + robotconfig) +target_link_libraries(MqttRosConnectionTestNode LINK_PUBLIC + ${catkin_LIBRARIES} + ${PahoMqtt3c} + ${PahoMqtt3cs} + ${PahoMqtt3a} + ${PahoMqtt3as} + ${PahoMqttCpp} + ${Protobuf_LIBRARIES} + dataconfig) target_link_libraries(TimedCartesianPlanner ${catkin_LIBRARIES}) \ No newline at end of file diff --git a/launch/move_group_interface_tutorial.launch b/launch/move_group_interface_tutorial.launch deleted file mode 100644 index 1fddc14f2140fb97e3673115025337328d043438..0000000000000000000000000000000000000000 --- a/launch/move_group_interface_tutorial.launch +++ /dev/null @@ -1,66 +0,0 @@ -<launch> - - <param name="robot_description" command="$(find xacro)/xacro $(find franka_description)/robots/panda_arm_hand.urdf.xacro" /> - - <!-- GAZEBO arguments --> - <arg name="paused" default="false" /> - <arg name="use_sim_time" default="true" /> - <arg name="gui" default="true" /> - <arg name="headless" default="false" /> - <arg name="debug" default="false" /> - <arg name="load_gripper" default="true" /> - - <!--launch GAZEBO with own world configuration --> - <include file="$(find gazebo_ros)/launch/empty_world.launch"> - <!-- <arg name="world_name" value="$(find robotics_assisted_tomography)/worlds/tomography.world"/> --> - <arg name="debug" value="$(arg debug)" /> - <arg name="gui" value="$(arg gui)" /> - <arg name="paused" value="$(arg paused)" /> - <arg name="use_sim_time" value="$(arg use_sim_time)" /> - <arg name="headless" value="$(arg headless)" /> - </include> - - <node name="rqt_console" pkg="rqt_console" type="rqt_console" /> - <!-- <node name="rqt_logger_level" pkg="rqt_logger_level" type="rqt_logger_level" /> --> - - <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model panda" /> - - <!-- Load joint controller configurations from YAML file to parameter server --> - <rosparam file="$(find panda_simulation)/config/panda_control.yaml" command="load" /> - - - <!-- load the controllers --> - <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="joint_state_controller panda_arm_controller" /> - <node if="$(arg load_gripper)" name="controller_spawner_hand" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="panda_hand_controller" /> - - - <!-- convert joint states to TF transforms for rviz, etc --> - <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" /> - - <include file="$(find panda_moveit_config)/launch/planning_context.launch"> - <arg name="load_robot_description" value="true" /> - <arg name="load_gripper" value="$(arg load_gripper)" /> - </include> - <include file="$(find panda_moveit_config)/launch/move_group.launch"> - <arg name="load_gripper" value="$(arg load_gripper)" /> - </include> - <group if="$(arg gui)"> - <include file="$(find panda_moveit_config)/launch/moveit_rviz.launch" /> - </group> - - <node name="joint_state_desired_publisher" pkg="topic_tools" type="relay" args="joint_states joint_states_desired" /> - - <!-- launch robot control node for moveit motion planning --> - <node pkg="panda_simulation" type="robot_control_node" name="robot_control_node" output="screen" /> - - <!-- load (not start!) custom joint position controller --> - <node pkg="controller_manager" type="spawner" name="joint_position_launcher" args="--stopped joint_position_controller" /> - - <!-- run custom node for automatic intialization --> - <node pkg="panda_simulation" type="robot_state_initializer_node" name="robot_state_initializer_node" /> - - <node pkg="panda_simulation" type="move_group_interface_tutorial" name="move_group_interface_tutorial" respawn="false" output="screen"> - - </node> - -</launch> diff --git a/launch/simulation.launch b/launch/simulation.launch index a982c720e046458a10b05d96603481485084859e..85616237eb2d0dbba041cf1791169752a10f0749 100644 --- a/launch/simulation.launch +++ b/launch/simulation.launch @@ -59,7 +59,9 @@ <!--<node name="move_group_interface_tutorial" pkg="panda_simulation" type="move_group_interface_tutorial" respawn="false" output="screen"/>--> - <node name="constraint_planner" pkg="panda_simulation" type="constraint_planner" respawn="false" output="screen"/> + <node name="SafetyAwarePlanner" pkg="panda_simulation" type="SafetyAwarePlanner" respawn="false" output="screen"> + <param name="message_redirect_rate" type="int" value="100" /> + </node> <!--<node name="motion_planning_api_tutorial" pkg="panda_simulation" type="motion_planning_api_tutorial" respawn="false" output="screen"> <rosparam command="load" file="$(find panda_moveit_config)/config/kinematics.yaml"/> diff --git a/launch/simulation_rosrag.launch b/launch/simulation_rosrag.launch index 918b565cb7dbe6e836b431d27fe33cc8d9cf6f06..6e6fb9a5247b1b83d542103369ae9458c07b96c6 100644 --- a/launch/simulation_rosrag.launch +++ b/launch/simulation_rosrag.launch @@ -59,6 +59,6 @@ <node name="TimedCartesianPlanner" pkg="panda_simulation" type="TimedCartesianPlanner" respawn="false" output="screen"/> <node name="MqttToRosNode" pkg="panda_simulation" type="MqttToRosNode" respawn="false" output="screen"/> - <node name="RobotStateProvider" pkg="panda_simulation" type="RobotStateProvider"/> + <node name="RobotStateProvider" pkg="panda_simulation" type="RobotStateProvider" respawn="false" output="screen"/> </launch> diff --git a/src/MqttRosConnectionTestNode.cpp b/src/MqttRosConnectionTestNode.cpp index 78134d9cd2f079be7e1b753d0e22db19b3b2c839..96f7eb569d0656df321b5e73cba3fc6786e9094c 100644 --- a/src/MqttRosConnectionTestNode.cpp +++ b/src/MqttRosConnectionTestNode.cpp @@ -5,8 +5,8 @@ #include <gazebo_msgs/LinkStates.h> #include <mqtt/client.h> #include "string.h" -#include "robotconfig.pb.h" -#include "dataconfig.pb.h" +#include "messages/robotconfig.pb.h" +#include "messages/dataconfig.pb.h" #include "mem_persistence.cpp" using namespace std; diff --git a/src/MqttToRosNode.cpp b/src/MqttToRosNode.cpp index ac714abdc4368ea21640e7e3114109be51266820..a2138029dc12390258c90a88b2536c87823d8b30 100644 --- a/src/MqttToRosNode.cpp +++ b/src/MqttToRosNode.cpp @@ -7,8 +7,8 @@ #include "ros/ros.h" -#include "robotconfig.pb.h" -#include "dataconfig.pb.h" +#include "messages/robotconfig.pb.h" +#include "messages/dataconfig.pb.h" using namespace std; using namespace std::chrono; @@ -16,9 +16,8 @@ using namespace std::chrono; const string SERVER_ADDRESS { "tcp://localhost:1883" }; const string CLIENT_ID { "ros_mqtt_consumer" }; -// -------------------------------------------------------------------------- -// Simple function to manually reconnect a client. +// Simple function to manually reconnect a client. bool try_reconnect(mqtt::client& cli) { constexpr int N_ATTEMPT = 30; @@ -35,8 +34,6 @@ bool try_reconnect(mqtt::client& cli) return false; } -///////////////////////////////////////////////////////////////////////////// - void handleRobotConfig(config::RobotConfig robotConfig, ros::NodeHandle n) { std::cout << "Retrieved new target-speed: " << robotConfig.speed() << std::endl; diff --git a/src/RobotStateProvider.cpp b/src/RobotStateProvider.cpp index 40a12c363742d7f6adfc5935cfc87a2079bcd6e6..cfd6878caf74a2a5b1aad0c08ccb38db18863a5b 100644 --- a/src/RobotStateProvider.cpp +++ b/src/RobotStateProvider.cpp @@ -5,7 +5,7 @@ #include <gazebo_msgs/LinkStates.h> #include <mqtt/client.h> #include "string.h" -#include "linkstate.pb.h" +#include "messages/linkstate.pb.h" #include "mem_persistence.cpp" bool export_to_log = false; diff --git a/src/SafetyAwarePlanner.cpp b/src/SafetyAwarePlanner.cpp index 460e9ae5efdee20eb5d37305c246c8a659916a8e..afe69ecc2e5f16c385af1bcaf82bee58570e8253 100644 --- a/src/SafetyAwarePlanner.cpp +++ b/src/SafetyAwarePlanner.cpp @@ -7,7 +7,7 @@ int main(int argc, char** argv) { - ros::init(argc, argv, "CONSTRAINT PLANNER"); + ros::init(argc, argv, "Safety-aware PLANNER"); ros::NodeHandle node_handle; ros::AsyncSpinner spinner(1); spinner.start(); @@ -27,15 +27,15 @@ int main(int argc, char** argv) Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); text_pose.translation().z() = 1.75; - visual_tools.publishText(text_pose, "Sample constraint planner node", rvt::WHITE, rvt::XLARGE); + visual_tools.publishText(text_pose, "Safety-aware planner node", rvt::WHITE, rvt::XLARGE); // Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations visual_tools.trigger(); // Getting Basic Information - ROS_INFO_NAMED("constraint_planner", "Planning frame: %s", move_group.getPlanningFrame().c_str()); - ROS_INFO_NAMED("constraint_planner", "End effector link: %s", move_group.getEndEffectorLink().c_str()); - ROS_INFO_NAMED("constraint_planner", "Available Planning Groups:"); + ROS_INFO_NAMED("safety_aware_planner", "Planning frame: %s", move_group.getPlanningFrame().c_str()); + ROS_INFO_NAMED("safety_aware_planner", "End effector link: %s", move_group.getEndEffectorLink().c_str()); + ROS_INFO_NAMED("safety_aware_planner", "Available Planning Groups:"); std::copy(move_group.getJointModelGroupNames().begin(), move_group.getJointModelGroupNames().end(), std::ostream_iterator<std::string>(std::cout, ", ")); @@ -64,7 +64,7 @@ int main(int argc, char** argv) //visual_tools.processCollisionObjectMsg(collision_objects[2], rviz_visual_tools::RED); // visual_tools.setAlpha(0.0); // Now, let's add the collision object into the world - ROS_INFO_NAMED("tutorial", "Add an object into the world"); + ROS_INFO_NAMED("safety_aware_planner", "Add an object into the world"); planning_scene_interface.addCollisionObjects(collision_objects); @@ -91,7 +91,7 @@ int main(int argc, char** argv) moveit::planning_interface::MoveGroupInterface::Plan my_plan; bool success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); - ROS_INFO_NAMED("constraint_planner", "Visualizing constraint plan %s", success ? "" : "FAILED"); + ROS_INFO_NAMED("safety_aware_planner", "Visualizing constraint plan %s", success ? "" : "FAILED"); visual_tools.prompt("Press 'next' to move the simulated robot."); visual_tools.trigger(); diff --git a/src/TimedCartesianPlanner.cpp b/src/TimedCartesianPlanner.cpp index cca05c9e50a8fb15698c9e28c87107fad4d8db42..cba8846281d729fc9e047c8ac4ccd817ebee69cc 100644 --- a/src/TimedCartesianPlanner.cpp +++ b/src/TimedCartesianPlanner.cpp @@ -2,7 +2,6 @@ // Created by sebastian on 31.03.20. // #include <moveit/move_group_interface/move_group_interface.h> -#include <moveit/planning_scene_interface/planning_scene_interface.h> #include <moveit_msgs/DisplayTrajectory.h> #include <moveit_msgs/CollisionObject.h> @@ -17,8 +16,7 @@ const double default_velocity = 1.0; bool isInitialized = false; -void initRawTrajectory(ros::NodeHandle node_handle, moveit::planning_interface::MoveGroupInterface* group) -{ +void initRawTrajectory(ros::NodeHandle node_handle, moveit::planning_interface::MoveGroupInterface *group) { geometry_msgs::Pose target_pose_1 = group->getCurrentPose().pose; geometry_msgs::Pose target_pose_2 = group->getCurrentPose().pose; geometry_msgs::Pose target_pose_3 = group->getCurrentPose().pose; @@ -45,8 +43,7 @@ void initRawTrajectory(ros::NodeHandle node_handle, moveit::planning_interface:: raw_trajectory.push_back(target_pose_4); } -void moveRobotToInitialState(ros::NodeHandle node_handle) -{ +void moveRobotToInitialState(ros::NodeHandle node_handle) { ROS_INFO("Moving to initial pose of trajectory."); moveit::planning_interface::MoveGroupInterface group("panda_arm"); @@ -71,8 +68,29 @@ void moveRobotToInitialState(ros::NodeHandle node_handle) group.execute(cartesian_plan); } -int main(int argc, char **argv) -{ +void computeTrajectory(moveit::planning_interface::MoveGroupInterface &group, int i, + moveit::planning_interface::MoveGroupInterface::Plan &plan, + moveit_msgs::RobotTrajectory &trajectory_msg) { + std::vector<geometry_msgs::Pose> single_traj; + single_traj.push_back(raw_trajectory.at(i)); + group.setStartStateToCurrentState(); + group.setPlanningTime(10.0); + double fraction = group.computeCartesianPath(single_traj, 0.01, 0.0, trajectory_msg, false); + + robot_trajectory::RobotTrajectory rt(group.getCurrentState()->getRobotModel(), "panda_arm"); + rt.setRobotTrajectoryMsg(*group.getCurrentState(), trajectory_msg); + trajectory_processing::IterativeParabolicTimeParameterization iptp; + + bool success = iptp.computeTimeStamps(rt); + ROS_INFO("Computed time stamp %s", success ? "SUCCEDED" : "FAILED"); + rt.getRobotTrajectoryMsg(trajectory_msg); + plan.trajectory_ = trajectory_msg; + ROS_INFO("Visualizing cartesian plan (%.2f%% acheived)", fraction * 100.0); +} + +int main(int argc, char **argv) { + + // setup this ros-node ros::init(argc, argv, "timed_cartesian_planner"); ros::NodeHandle node_handle; ros::AsyncSpinner spinner(1); @@ -91,7 +109,7 @@ int main(int argc, char **argv) Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); text_pose.translation().z() = 1.75; - visual_tools.publishText(text_pose, "Sample constraint planner node", rvt::WHITE, rvt::XLARGE); + visual_tools.publishText(text_pose, "cartesian planner node", rvt::WHITE, rvt::XLARGE); visual_tools.trigger(); // Initialize start state of robot and target trajectory. @@ -99,69 +117,42 @@ int main(int argc, char **argv) moveRobotToInitialState(node_handle); initRawTrajectory(node_handle, &group); - for(int i = 0; i < raw_trajectory.size(); i++) - { + // execute the trajectory which consists of single waypoints to allow distinct planning + for (int i = 0; i < raw_trajectory.size(); i++) { double velocity = 0.0; - if(!node_handle.getParam("robot_speed_factor", velocity)) - { + if (!node_handle.getParam("robot_speed_factor", velocity)) { velocity = default_velocity; } - std::cout << ">>>>>>>>>>>>>>>>> starting planing step " << i << " (speed: " << velocity << ")" << std::endl; - - std::vector<geometry_msgs::Pose> single_traj; - single_traj.push_back(raw_trajectory.at(i)); - - moveit::planning_interface::MoveGroupInterface group("panda_arm"); - moveit::planning_interface::PlanningSceneInterface planning_scene_interface; - - ros::Publisher display_publisher = node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true); + std::cout << ">>>>>>>>>>>>>>>>> starting planing step " << i << " (speed: " << velocity << ")" << std::endl; + // compute the cartesian trajectory moveit::planning_interface::MoveGroupInterface::Plan plan; - group.setStartStateToCurrentState(); - moveit_msgs::RobotTrajectory trajectory_msg; - group.setPlanningTime(10.0); - - double fraction = group.computeCartesianPath(single_traj,0.01,0.0,trajectory_msg, false); - robot_trajectory::RobotTrajectory rt(group.getCurrentState()->getRobotModel(), "panda_arm"); - rt.setRobotTrajectoryMsg(*group.getCurrentState(), trajectory_msg); - - // Third create a IterativeParabolicTimeParameterization object - trajectory_processing::IterativeParabolicTimeParameterization iptp; - // Fourth compute computeTimeStamps - bool success = iptp.computeTimeStamps(rt); - ROS_INFO("Computed time stamp %s",success ? "SUCCEDED":"FAILED"); - rt.getRobotTrajectoryMsg(trajectory_msg); - plan.trajectory_ = trajectory_msg; - ROS_INFO("Visualizing cartesian plan (%.2f%% acheived)",fraction * 100.0); - - //std::cout << ">>>>>>>>>>>>>>>>> data before: " << trajectory_msg << std::endl; - // adjust velocities, accelerations and time_from_start - for(int i = 0; i < trajectory_msg.joint_trajectory.points.size(); i++) - { + computeTrajectory(group, i, plan, trajectory_msg); + + // adjust velocities, accelerations (= sqrt of velocity) and time_from_start + for (int i = 0; i < trajectory_msg.joint_trajectory.points.size(); i++) { double new_tfs = 1 / velocity; trajectory_msg.joint_trajectory.points[i].time_from_start.operator*=(new_tfs); - for(int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).velocities.size(); j++) - { - if(trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) != 0.0){ + for (int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).velocities.size(); j++) { + if (trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) != 0.0) { trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) *= velocity; } } - for(int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).accelerations.size(); j++) - { + for (int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).accelerations.size(); j++) { trajectory_msg.joint_trajectory.points.at(i).accelerations.at(j) = sqrt(std::abs(trajectory_msg.joint_trajectory.points.at(i).accelerations.at(j))); } } - //std::cout << ">>>>>>>>>>>>>>>>> data after: " << trajectory_msg << std::endl; + // execute one step of the trajectory group.execute(plan); - if(i == (raw_trajectory.size() -1)) - { + // make sure the robot moves in an infinite circle + if (i == (raw_trajectory.size() - 1)) { i = -1; } } diff --git a/src/box_publisher.cpp b/src/box_publisher.cpp deleted file mode 100644 index 339f3f292f420a8e37c8124975e7fb5191948c3a..0000000000000000000000000000000000000000 --- a/src/box_publisher.cpp +++ /dev/null @@ -1,71 +0,0 @@ -#include <gazebo_msgs/SetModelState.h> -#include <moveit/move_group_interface/move_group_interface.h> -#include <moveit/robot_model_loader/robot_model_loader.h> -#include <ros/ros.h> -#include <sensor_msgs/JointState.h> - -static const std::string PLANNING_GROUP_ARM = "panda_arm"; -static const double PANDA_ARM_TO_HAND_OFFSET = 0.12; -static const double PANDA_HAND_TO_FINGER_OFFSET = 0.04; -ros::Publisher gazebo_model_state_pub; -robot_model::RobotModelPtr kinematic_model; -robot_state::RobotStatePtr kinematic_state; - -void jointStatesCallback(const sensor_msgs::JointState &joint_states_current) -{ - const robot_state::JointModelGroup *joint_model_group = kinematic_model->getJointModelGroup("panda_arm"); - const std::vector<std::string> &joint_names = joint_model_group->getJointModelNames(); - - std::vector<double> joint_states; - for (size_t i = 0; i < joint_states_current.position.size() - 2; ++i) - { - joint_states.push_back(joint_states_current.position[i + 2]); - } - kinematic_state->setJointGroupPositions(joint_model_group, joint_states); - - const Eigen::Affine3d &end_effector_state = kinematic_state->getGlobalLinkTransform("panda_link8"); - - double end_effector_z_offset = PANDA_ARM_TO_HAND_OFFSET + PANDA_HAND_TO_FINGER_OFFSET; - Eigen::Affine3d tmp_transform(Eigen::Translation3d(Eigen::Vector3d(0.0, 0.0, end_effector_z_offset))); - - Eigen::Affine3d newState = end_effector_state * tmp_transform; - - geometry_msgs::Pose pose; - pose.position.x = newState.translation().x(); - pose.position.y = newState.translation().y(); - pose.position.z = newState.translation().z(); - - Eigen::Quaterniond quat(newState.rotation()); - pose.orientation.w = quat.w(); - pose.orientation.x = quat.x(); - pose.orientation.y = quat.y(); - pose.orientation.z = quat.z(); - - ROS_DEBUG_STREAM("translation" << std::endl << newState.translation()); - ROS_DEBUG_STREAM("rotation" << std::endl << newState.rotation()); - - gazebo_msgs::ModelState model_state; - // This string results from the spawn_urdf call in the box.launch file argument: -model box - model_state.model_name = std::string("box"); - model_state.pose = pose; - model_state.reference_frame = std::string("world"); - - gazebo_model_state_pub.publish(model_state); -} - -int main(int argc, char **argv) -{ - ros::init(argc, argv, "box_publisher_node"); - ros::NodeHandle node_handle; - - ros::Subscriber joint_states_sub = node_handle.subscribe("/joint_states", 1, jointStatesCallback); - - robot_model_loader::RobotModelLoader robot_model_loader("robot_description"); - kinematic_model = robot_model_loader.getModel(); - kinematic_state = robot_state::RobotStatePtr(new robot_state::RobotState(kinematic_model)); - - gazebo_model_state_pub = node_handle.advertise<gazebo_msgs::ModelState>("/gazebo/set_model_state", 1); - - ros::spin(); - return 0; -} \ No newline at end of file diff --git a/src/dataconfig.pb.cc b/src/messages/dataconfig.pb.cc similarity index 100% rename from src/dataconfig.pb.cc rename to src/messages/dataconfig.pb.cc diff --git a/src/dataconfig.pb.h b/src/messages/dataconfig.pb.h similarity index 100% rename from src/dataconfig.pb.h rename to src/messages/dataconfig.pb.h diff --git a/src/messages/linkstate.pb.cc b/src/messages/linkstate.pb.cc new file mode 100644 index 0000000000000000000000000000000000000000..5532aae19298c37571c6f606c84f4344c6c689b4 --- /dev/null +++ b/src/messages/linkstate.pb.cc @@ -0,0 +1,2693 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: linkstate.proto + +#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION +#include "linkstate.pb.h" + +#include <algorithm> + +#include <google/protobuf/stubs/common.h> +#include <google/protobuf/stubs/port.h> +#include <google/protobuf/stubs/once.h> +#include <google/protobuf/io/coded_stream.h> +#include <google/protobuf/wire_format_lite_inl.h> +#include <google/protobuf/descriptor.h> +#include <google/protobuf/generated_message_reflection.h> +#include <google/protobuf/reflection_ops.h> +#include <google/protobuf/wire_format.h> +// @@protoc_insertion_point(includes) + +namespace panda { + +namespace { + +const ::google::protobuf::Descriptor* PandaLinkState_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PandaLinkState_reflection_ = NULL; +const ::google::protobuf::Descriptor* PandaLinkState_Position_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PandaLinkState_Position_reflection_ = NULL; +const ::google::protobuf::Descriptor* PandaLinkState_Orientation_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PandaLinkState_Orientation_reflection_ = NULL; +const ::google::protobuf::Descriptor* PandaLinkState_TwistLinear_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PandaLinkState_TwistLinear_reflection_ = NULL; +const ::google::protobuf::Descriptor* PandaLinkState_TwistAngular_descriptor_ = NULL; +const ::google::protobuf::internal::GeneratedMessageReflection* + PandaLinkState_TwistAngular_reflection_ = NULL; + +} // namespace + + +void protobuf_AssignDesc_linkstate_2eproto() GOOGLE_ATTRIBUTE_COLD; +void protobuf_AssignDesc_linkstate_2eproto() { + protobuf_AddDesc_linkstate_2eproto(); + const ::google::protobuf::FileDescriptor* file = + ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName( + "linkstate.proto"); + GOOGLE_CHECK(file != NULL); + PandaLinkState_descriptor_ = file->message_type(0); + static const int PandaLinkState_offsets_[5] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, name_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, pos_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, orient_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, tl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, ta_), + }; + PandaLinkState_reflection_ = + ::google::protobuf::internal::GeneratedMessageReflection::NewGeneratedMessageReflection( + PandaLinkState_descriptor_, + PandaLinkState::default_instance_, + PandaLinkState_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, _has_bits_[0]), + -1, + -1, + sizeof(PandaLinkState), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState, _internal_metadata_), + -1); + PandaLinkState_Position_descriptor_ = PandaLinkState_descriptor_->nested_type(0); + static const int PandaLinkState_Position_offsets_[3] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Position, positionx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Position, positiony_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Position, positionz_), + }; + PandaLinkState_Position_reflection_ = + ::google::protobuf::internal::GeneratedMessageReflection::NewGeneratedMessageReflection( + PandaLinkState_Position_descriptor_, + PandaLinkState_Position::default_instance_, + PandaLinkState_Position_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Position, _has_bits_[0]), + -1, + -1, + sizeof(PandaLinkState_Position), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Position, _internal_metadata_), + -1); + PandaLinkState_Orientation_descriptor_ = PandaLinkState_descriptor_->nested_type(1); + static const int PandaLinkState_Orientation_offsets_[4] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, orientationx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, orientationy_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, orientationz_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, orientationw_), + }; + PandaLinkState_Orientation_reflection_ = + ::google::protobuf::internal::GeneratedMessageReflection::NewGeneratedMessageReflection( + PandaLinkState_Orientation_descriptor_, + PandaLinkState_Orientation::default_instance_, + PandaLinkState_Orientation_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, _has_bits_[0]), + -1, + -1, + sizeof(PandaLinkState_Orientation), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_Orientation, _internal_metadata_), + -1); + PandaLinkState_TwistLinear_descriptor_ = PandaLinkState_descriptor_->nested_type(2); + static const int PandaLinkState_TwistLinear_offsets_[3] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistLinear, twistlinearx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistLinear, twistlineary_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistLinear, twistlinearz_), + }; + PandaLinkState_TwistLinear_reflection_ = + ::google::protobuf::internal::GeneratedMessageReflection::NewGeneratedMessageReflection( + PandaLinkState_TwistLinear_descriptor_, + PandaLinkState_TwistLinear::default_instance_, + PandaLinkState_TwistLinear_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistLinear, _has_bits_[0]), + -1, + -1, + sizeof(PandaLinkState_TwistLinear), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistLinear, _internal_metadata_), + -1); + PandaLinkState_TwistAngular_descriptor_ = PandaLinkState_descriptor_->nested_type(3); + static const int PandaLinkState_TwistAngular_offsets_[3] = { + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistAngular, twistangularx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistAngular, twistangulary_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistAngular, twistangularz_), + }; + PandaLinkState_TwistAngular_reflection_ = + ::google::protobuf::internal::GeneratedMessageReflection::NewGeneratedMessageReflection( + PandaLinkState_TwistAngular_descriptor_, + PandaLinkState_TwistAngular::default_instance_, + PandaLinkState_TwistAngular_offsets_, + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistAngular, _has_bits_[0]), + -1, + -1, + sizeof(PandaLinkState_TwistAngular), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PandaLinkState_TwistAngular, _internal_metadata_), + -1); +} + +namespace { + +GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_); +inline void protobuf_AssignDescriptorsOnce() { + ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_, + &protobuf_AssignDesc_linkstate_2eproto); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PandaLinkState_descriptor_, &PandaLinkState::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PandaLinkState_Position_descriptor_, &PandaLinkState_Position::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PandaLinkState_Orientation_descriptor_, &PandaLinkState_Orientation::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PandaLinkState_TwistLinear_descriptor_, &PandaLinkState_TwistLinear::default_instance()); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( + PandaLinkState_TwistAngular_descriptor_, &PandaLinkState_TwistAngular::default_instance()); +} + +} // namespace + +void protobuf_ShutdownFile_linkstate_2eproto() { + delete PandaLinkState::default_instance_; + delete PandaLinkState_reflection_; + delete PandaLinkState_Position::default_instance_; + delete PandaLinkState_Position_reflection_; + delete PandaLinkState_Orientation::default_instance_; + delete PandaLinkState_Orientation_reflection_; + delete PandaLinkState_TwistLinear::default_instance_; + delete PandaLinkState_TwistLinear_reflection_; + delete PandaLinkState_TwistAngular::default_instance_; + delete PandaLinkState_TwistAngular_reflection_; +} + +void protobuf_AddDesc_linkstate_2eproto() GOOGLE_ATTRIBUTE_COLD; +void protobuf_AddDesc_linkstate_2eproto() { + static bool already_here = false; + if (already_here) return; + already_here = true; + GOOGLE_PROTOBUF_VERIFY_VERSION; + + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + "\n\017linkstate.proto\022\005panda\"\257\004\n\016PandaLinkSt" + "ate\022\014\n\004name\030\001 \002(\t\022+\n\003pos\030\002 \001(\0132\036.panda.P" + "andaLinkState.Position\0221\n\006orient\030\003 \001(\0132!" + ".panda.PandaLinkState.Orientation\022-\n\002tl\030" + "\004 \001(\0132!.panda.PandaLinkState.TwistLinear" + "\022.\n\002ta\030\005 \001(\0132\".panda.PandaLinkState.Twis" + "tAngular\032C\n\010Position\022\021\n\tpositionX\030\001 \002(\002\022" + "\021\n\tpositionY\030\002 \002(\002\022\021\n\tpositionZ\030\003 \002(\002\032e\n" + "\013Orientation\022\024\n\014orientationX\030\001 \002(\002\022\024\n\014or" + "ientationY\030\002 \002(\002\022\024\n\014orientationZ\030\003 \002(\002\022\024" + "\n\014orientationW\030\004 \002(\002\032O\n\013TwistLinear\022\024\n\014t" + "wistLinearX\030\001 \002(\002\022\024\n\014twistLinearY\030\002 \002(\002\022" + "\024\n\014twistLinearZ\030\003 \002(\002\032S\n\014TwistAngular\022\025\n" + "\rtwistAngularX\030\001 \002(\002\022\025\n\rtwistAngularY\030\002 " + "\002(\002\022\025\n\rtwistAngularZ\030\003 \002(\002", 586); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "linkstate.proto", &protobuf_RegisterTypes); + PandaLinkState::default_instance_ = new PandaLinkState(); + PandaLinkState_Position::default_instance_ = new PandaLinkState_Position(); + PandaLinkState_Orientation::default_instance_ = new PandaLinkState_Orientation(); + PandaLinkState_TwistLinear::default_instance_ = new PandaLinkState_TwistLinear(); + PandaLinkState_TwistAngular::default_instance_ = new PandaLinkState_TwistAngular(); + PandaLinkState::default_instance_->InitAsDefaultInstance(); + PandaLinkState_Position::default_instance_->InitAsDefaultInstance(); + PandaLinkState_Orientation::default_instance_->InitAsDefaultInstance(); + PandaLinkState_TwistLinear::default_instance_->InitAsDefaultInstance(); + PandaLinkState_TwistAngular::default_instance_->InitAsDefaultInstance(); + ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_linkstate_2eproto); +} + +// Force AddDescriptors() to be called at static initialization time. +struct StaticDescriptorInitializer_linkstate_2eproto { + StaticDescriptorInitializer_linkstate_2eproto() { + protobuf_AddDesc_linkstate_2eproto(); + } +} static_descriptor_initializer_linkstate_2eproto_; + +// =================================================================== + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PandaLinkState_Position::kPositionXFieldNumber; +const int PandaLinkState_Position::kPositionYFieldNumber; +const int PandaLinkState_Position::kPositionZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PandaLinkState_Position::PandaLinkState_Position() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + SharedCtor(); + // @@protoc_insertion_point(constructor:panda.PandaLinkState.Position) +} + +void PandaLinkState_Position::InitAsDefaultInstance() { +} + +PandaLinkState_Position::PandaLinkState_Position(const PandaLinkState_Position& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + SharedCtor(); + MergeFrom(from); + // @@protoc_insertion_point(copy_constructor:panda.PandaLinkState.Position) +} + +void PandaLinkState_Position::SharedCtor() { + _cached_size_ = 0; + positionx_ = 0; + positiony_ = 0; + positionz_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PandaLinkState_Position::~PandaLinkState_Position() { + // @@protoc_insertion_point(destructor:panda.PandaLinkState.Position) + SharedDtor(); +} + +void PandaLinkState_Position::SharedDtor() { + if (this != default_instance_) { + } +} + +void PandaLinkState_Position::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PandaLinkState_Position::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PandaLinkState_Position_descriptor_; +} + +const PandaLinkState_Position& PandaLinkState_Position::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_linkstate_2eproto(); + return *default_instance_; +} + +PandaLinkState_Position* PandaLinkState_Position::default_instance_ = NULL; + +PandaLinkState_Position* PandaLinkState_Position::New(::google::protobuf::Arena* arena) const { + PandaLinkState_Position* n = new PandaLinkState_Position; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PandaLinkState_Position::Clear() { +// @@protoc_insertion_point(message_clear_start:panda.PandaLinkState.Position) +#if defined(__clang__) +#define ZR_HELPER_(f) \ + _Pragma("clang diagnostic push") \ + _Pragma("clang diagnostic ignored \"-Winvalid-offsetof\"") \ + __builtin_offsetof(PandaLinkState_Position, f) \ + _Pragma("clang diagnostic pop") +#else +#define ZR_HELPER_(f) reinterpret_cast<char*>(\ + &reinterpret_cast<PandaLinkState_Position*>(16)->f) +#endif + +#define ZR_(first, last) do {\ + ::memset(&first, 0,\ + ZR_HELPER_(last) - ZR_HELPER_(first) + sizeof(last));\ +} while (0) + + ZR_(positionx_, positionz_); + +#undef ZR_HELPER_ +#undef ZR_ + + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + if (_internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->Clear(); + } +} + +bool PandaLinkState_Position::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:panda.PandaLinkState.Position) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float positionX = 1; + case 1: { + if (tag == 13) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &positionx_))); + set_has_positionx(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(21)) goto parse_positionY; + break; + } + + // required float positionY = 2; + case 2: { + if (tag == 21) { + parse_positionY: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &positiony_))); + set_has_positiony(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(29)) goto parse_positionZ; + break; + } + + // required float positionZ = 3; + case 3: { + if (tag == 29) { + parse_positionZ: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &positionz_))); + set_has_positionz(); + } else { + goto handle_unusual; + } + if (input->ExpectAtEnd()) goto success; + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:panda.PandaLinkState.Position) + return true; +failure: + // @@protoc_insertion_point(parse_failure:panda.PandaLinkState.Position) + return false; +#undef DO_ +} + +void PandaLinkState_Position::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:panda.PandaLinkState.Position) + // required float positionX = 1; + if (has_positionx()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->positionx(), output); + } + + // required float positionY = 2; + if (has_positiony()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->positiony(), output); + } + + // required float positionZ = 3; + if (has_positionz()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->positionz(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:panda.PandaLinkState.Position) +} + +::google::protobuf::uint8* PandaLinkState_Position::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:panda.PandaLinkState.Position) + // required float positionX = 1; + if (has_positionx()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->positionx(), target); + } + + // required float positionY = 2; + if (has_positiony()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->positiony(), target); + } + + // required float positionZ = 3; + if (has_positionz()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->positionz(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:panda.PandaLinkState.Position) + return target; +} + +int PandaLinkState_Position::RequiredFieldsByteSizeFallback() const { +// @@protoc_insertion_point(required_fields_byte_size_fallback_start:panda.PandaLinkState.Position) + int total_size = 0; + + if (has_positionx()) { + // required float positionX = 1; + total_size += 1 + 4; + } + + if (has_positiony()) { + // required float positionY = 2; + total_size += 1 + 4; + } + + if (has_positionz()) { + // required float positionZ = 3; + total_size += 1 + 4; + } + + return total_size; +} +int PandaLinkState_Position::ByteSize() const { +// @@protoc_insertion_point(message_byte_size_start:panda.PandaLinkState.Position) + int total_size = 0; + + if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) { // All required fields are present. + // required float positionX = 1; + total_size += 1 + 4; + + // required float positionY = 2; + total_size += 1 + 4; + + // required float positionZ = 3; + total_size += 1 + 4; + + } else { + total_size += RequiredFieldsByteSizeFallback(); + } + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PandaLinkState_Position::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:panda.PandaLinkState.Position) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + const PandaLinkState_Position* source = + ::google::protobuf::internal::DynamicCastToGenerated<const PandaLinkState_Position>( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:panda.PandaLinkState.Position) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:panda.PandaLinkState.Position) + MergeFrom(*source); + } +} + +void PandaLinkState_Position::MergeFrom(const PandaLinkState_Position& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:panda.PandaLinkState.Position) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_positionx()) { + set_positionx(from.positionx()); + } + if (from.has_positiony()) { + set_positiony(from.positiony()); + } + if (from.has_positionz()) { + set_positionz(from.positionz()); + } + } + if (from._internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); + } +} + +void PandaLinkState_Position::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:panda.PandaLinkState.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PandaLinkState_Position::CopyFrom(const PandaLinkState_Position& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:panda.PandaLinkState.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PandaLinkState_Position::IsInitialized() const { + if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; + + return true; +} + +void PandaLinkState_Position::Swap(PandaLinkState_Position* other) { + if (other == this) return; + InternalSwap(other); +} +void PandaLinkState_Position::InternalSwap(PandaLinkState_Position* other) { + std::swap(positionx_, other->positionx_); + std::swap(positiony_, other->positiony_); + std::swap(positionz_, other->positionz_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PandaLinkState_Position::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PandaLinkState_Position_descriptor_; + metadata.reflection = PandaLinkState_Position_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PandaLinkState_Orientation::kOrientationXFieldNumber; +const int PandaLinkState_Orientation::kOrientationYFieldNumber; +const int PandaLinkState_Orientation::kOrientationZFieldNumber; +const int PandaLinkState_Orientation::kOrientationWFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PandaLinkState_Orientation::PandaLinkState_Orientation() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + SharedCtor(); + // @@protoc_insertion_point(constructor:panda.PandaLinkState.Orientation) +} + +void PandaLinkState_Orientation::InitAsDefaultInstance() { +} + +PandaLinkState_Orientation::PandaLinkState_Orientation(const PandaLinkState_Orientation& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + SharedCtor(); + MergeFrom(from); + // @@protoc_insertion_point(copy_constructor:panda.PandaLinkState.Orientation) +} + +void PandaLinkState_Orientation::SharedCtor() { + _cached_size_ = 0; + orientationx_ = 0; + orientationy_ = 0; + orientationz_ = 0; + orientationw_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PandaLinkState_Orientation::~PandaLinkState_Orientation() { + // @@protoc_insertion_point(destructor:panda.PandaLinkState.Orientation) + SharedDtor(); +} + +void PandaLinkState_Orientation::SharedDtor() { + if (this != default_instance_) { + } +} + +void PandaLinkState_Orientation::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PandaLinkState_Orientation::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PandaLinkState_Orientation_descriptor_; +} + +const PandaLinkState_Orientation& PandaLinkState_Orientation::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_linkstate_2eproto(); + return *default_instance_; +} + +PandaLinkState_Orientation* PandaLinkState_Orientation::default_instance_ = NULL; + +PandaLinkState_Orientation* PandaLinkState_Orientation::New(::google::protobuf::Arena* arena) const { + PandaLinkState_Orientation* n = new PandaLinkState_Orientation; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PandaLinkState_Orientation::Clear() { +// @@protoc_insertion_point(message_clear_start:panda.PandaLinkState.Orientation) +#if defined(__clang__) +#define ZR_HELPER_(f) \ + _Pragma("clang diagnostic push") \ + _Pragma("clang diagnostic ignored \"-Winvalid-offsetof\"") \ + __builtin_offsetof(PandaLinkState_Orientation, f) \ + _Pragma("clang diagnostic pop") +#else +#define ZR_HELPER_(f) reinterpret_cast<char*>(\ + &reinterpret_cast<PandaLinkState_Orientation*>(16)->f) +#endif + +#define ZR_(first, last) do {\ + ::memset(&first, 0,\ + ZR_HELPER_(last) - ZR_HELPER_(first) + sizeof(last));\ +} while (0) + + ZR_(orientationx_, orientationw_); + +#undef ZR_HELPER_ +#undef ZR_ + + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + if (_internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->Clear(); + } +} + +bool PandaLinkState_Orientation::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:panda.PandaLinkState.Orientation) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float orientationX = 1; + case 1: { + if (tag == 13) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &orientationx_))); + set_has_orientationx(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(21)) goto parse_orientationY; + break; + } + + // required float orientationY = 2; + case 2: { + if (tag == 21) { + parse_orientationY: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &orientationy_))); + set_has_orientationy(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(29)) goto parse_orientationZ; + break; + } + + // required float orientationZ = 3; + case 3: { + if (tag == 29) { + parse_orientationZ: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &orientationz_))); + set_has_orientationz(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(37)) goto parse_orientationW; + break; + } + + // required float orientationW = 4; + case 4: { + if (tag == 37) { + parse_orientationW: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &orientationw_))); + set_has_orientationw(); + } else { + goto handle_unusual; + } + if (input->ExpectAtEnd()) goto success; + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:panda.PandaLinkState.Orientation) + return true; +failure: + // @@protoc_insertion_point(parse_failure:panda.PandaLinkState.Orientation) + return false; +#undef DO_ +} + +void PandaLinkState_Orientation::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:panda.PandaLinkState.Orientation) + // required float orientationX = 1; + if (has_orientationx()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->orientationx(), output); + } + + // required float orientationY = 2; + if (has_orientationy()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->orientationy(), output); + } + + // required float orientationZ = 3; + if (has_orientationz()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->orientationz(), output); + } + + // required float orientationW = 4; + if (has_orientationw()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->orientationw(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:panda.PandaLinkState.Orientation) +} + +::google::protobuf::uint8* PandaLinkState_Orientation::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:panda.PandaLinkState.Orientation) + // required float orientationX = 1; + if (has_orientationx()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->orientationx(), target); + } + + // required float orientationY = 2; + if (has_orientationy()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->orientationy(), target); + } + + // required float orientationZ = 3; + if (has_orientationz()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->orientationz(), target); + } + + // required float orientationW = 4; + if (has_orientationw()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->orientationw(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:panda.PandaLinkState.Orientation) + return target; +} + +int PandaLinkState_Orientation::RequiredFieldsByteSizeFallback() const { +// @@protoc_insertion_point(required_fields_byte_size_fallback_start:panda.PandaLinkState.Orientation) + int total_size = 0; + + if (has_orientationx()) { + // required float orientationX = 1; + total_size += 1 + 4; + } + + if (has_orientationy()) { + // required float orientationY = 2; + total_size += 1 + 4; + } + + if (has_orientationz()) { + // required float orientationZ = 3; + total_size += 1 + 4; + } + + if (has_orientationw()) { + // required float orientationW = 4; + total_size += 1 + 4; + } + + return total_size; +} +int PandaLinkState_Orientation::ByteSize() const { +// @@protoc_insertion_point(message_byte_size_start:panda.PandaLinkState.Orientation) + int total_size = 0; + + if (((_has_bits_[0] & 0x0000000f) ^ 0x0000000f) == 0) { // All required fields are present. + // required float orientationX = 1; + total_size += 1 + 4; + + // required float orientationY = 2; + total_size += 1 + 4; + + // required float orientationZ = 3; + total_size += 1 + 4; + + // required float orientationW = 4; + total_size += 1 + 4; + + } else { + total_size += RequiredFieldsByteSizeFallback(); + } + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PandaLinkState_Orientation::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:panda.PandaLinkState.Orientation) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + const PandaLinkState_Orientation* source = + ::google::protobuf::internal::DynamicCastToGenerated<const PandaLinkState_Orientation>( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:panda.PandaLinkState.Orientation) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:panda.PandaLinkState.Orientation) + MergeFrom(*source); + } +} + +void PandaLinkState_Orientation::MergeFrom(const PandaLinkState_Orientation& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:panda.PandaLinkState.Orientation) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_orientationx()) { + set_orientationx(from.orientationx()); + } + if (from.has_orientationy()) { + set_orientationy(from.orientationy()); + } + if (from.has_orientationz()) { + set_orientationz(from.orientationz()); + } + if (from.has_orientationw()) { + set_orientationw(from.orientationw()); + } + } + if (from._internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); + } +} + +void PandaLinkState_Orientation::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:panda.PandaLinkState.Orientation) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PandaLinkState_Orientation::CopyFrom(const PandaLinkState_Orientation& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:panda.PandaLinkState.Orientation) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PandaLinkState_Orientation::IsInitialized() const { + if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; + + return true; +} + +void PandaLinkState_Orientation::Swap(PandaLinkState_Orientation* other) { + if (other == this) return; + InternalSwap(other); +} +void PandaLinkState_Orientation::InternalSwap(PandaLinkState_Orientation* other) { + std::swap(orientationx_, other->orientationx_); + std::swap(orientationy_, other->orientationy_); + std::swap(orientationz_, other->orientationz_); + std::swap(orientationw_, other->orientationw_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PandaLinkState_Orientation::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PandaLinkState_Orientation_descriptor_; + metadata.reflection = PandaLinkState_Orientation_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PandaLinkState_TwistLinear::kTwistLinearXFieldNumber; +const int PandaLinkState_TwistLinear::kTwistLinearYFieldNumber; +const int PandaLinkState_TwistLinear::kTwistLinearZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PandaLinkState_TwistLinear::PandaLinkState_TwistLinear() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + SharedCtor(); + // @@protoc_insertion_point(constructor:panda.PandaLinkState.TwistLinear) +} + +void PandaLinkState_TwistLinear::InitAsDefaultInstance() { +} + +PandaLinkState_TwistLinear::PandaLinkState_TwistLinear(const PandaLinkState_TwistLinear& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + SharedCtor(); + MergeFrom(from); + // @@protoc_insertion_point(copy_constructor:panda.PandaLinkState.TwistLinear) +} + +void PandaLinkState_TwistLinear::SharedCtor() { + _cached_size_ = 0; + twistlinearx_ = 0; + twistlineary_ = 0; + twistlinearz_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PandaLinkState_TwistLinear::~PandaLinkState_TwistLinear() { + // @@protoc_insertion_point(destructor:panda.PandaLinkState.TwistLinear) + SharedDtor(); +} + +void PandaLinkState_TwistLinear::SharedDtor() { + if (this != default_instance_) { + } +} + +void PandaLinkState_TwistLinear::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PandaLinkState_TwistLinear::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PandaLinkState_TwistLinear_descriptor_; +} + +const PandaLinkState_TwistLinear& PandaLinkState_TwistLinear::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_linkstate_2eproto(); + return *default_instance_; +} + +PandaLinkState_TwistLinear* PandaLinkState_TwistLinear::default_instance_ = NULL; + +PandaLinkState_TwistLinear* PandaLinkState_TwistLinear::New(::google::protobuf::Arena* arena) const { + PandaLinkState_TwistLinear* n = new PandaLinkState_TwistLinear; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PandaLinkState_TwistLinear::Clear() { +// @@protoc_insertion_point(message_clear_start:panda.PandaLinkState.TwistLinear) +#if defined(__clang__) +#define ZR_HELPER_(f) \ + _Pragma("clang diagnostic push") \ + _Pragma("clang diagnostic ignored \"-Winvalid-offsetof\"") \ + __builtin_offsetof(PandaLinkState_TwistLinear, f) \ + _Pragma("clang diagnostic pop") +#else +#define ZR_HELPER_(f) reinterpret_cast<char*>(\ + &reinterpret_cast<PandaLinkState_TwistLinear*>(16)->f) +#endif + +#define ZR_(first, last) do {\ + ::memset(&first, 0,\ + ZR_HELPER_(last) - ZR_HELPER_(first) + sizeof(last));\ +} while (0) + + ZR_(twistlinearx_, twistlinearz_); + +#undef ZR_HELPER_ +#undef ZR_ + + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + if (_internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->Clear(); + } +} + +bool PandaLinkState_TwistLinear::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:panda.PandaLinkState.TwistLinear) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float twistLinearX = 1; + case 1: { + if (tag == 13) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistlinearx_))); + set_has_twistlinearx(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(21)) goto parse_twistLinearY; + break; + } + + // required float twistLinearY = 2; + case 2: { + if (tag == 21) { + parse_twistLinearY: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistlineary_))); + set_has_twistlineary(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(29)) goto parse_twistLinearZ; + break; + } + + // required float twistLinearZ = 3; + case 3: { + if (tag == 29) { + parse_twistLinearZ: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistlinearz_))); + set_has_twistlinearz(); + } else { + goto handle_unusual; + } + if (input->ExpectAtEnd()) goto success; + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:panda.PandaLinkState.TwistLinear) + return true; +failure: + // @@protoc_insertion_point(parse_failure:panda.PandaLinkState.TwistLinear) + return false; +#undef DO_ +} + +void PandaLinkState_TwistLinear::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:panda.PandaLinkState.TwistLinear) + // required float twistLinearX = 1; + if (has_twistlinearx()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->twistlinearx(), output); + } + + // required float twistLinearY = 2; + if (has_twistlineary()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->twistlineary(), output); + } + + // required float twistLinearZ = 3; + if (has_twistlinearz()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->twistlinearz(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:panda.PandaLinkState.TwistLinear) +} + +::google::protobuf::uint8* PandaLinkState_TwistLinear::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:panda.PandaLinkState.TwistLinear) + // required float twistLinearX = 1; + if (has_twistlinearx()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->twistlinearx(), target); + } + + // required float twistLinearY = 2; + if (has_twistlineary()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->twistlineary(), target); + } + + // required float twistLinearZ = 3; + if (has_twistlinearz()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->twistlinearz(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:panda.PandaLinkState.TwistLinear) + return target; +} + +int PandaLinkState_TwistLinear::RequiredFieldsByteSizeFallback() const { +// @@protoc_insertion_point(required_fields_byte_size_fallback_start:panda.PandaLinkState.TwistLinear) + int total_size = 0; + + if (has_twistlinearx()) { + // required float twistLinearX = 1; + total_size += 1 + 4; + } + + if (has_twistlineary()) { + // required float twistLinearY = 2; + total_size += 1 + 4; + } + + if (has_twistlinearz()) { + // required float twistLinearZ = 3; + total_size += 1 + 4; + } + + return total_size; +} +int PandaLinkState_TwistLinear::ByteSize() const { +// @@protoc_insertion_point(message_byte_size_start:panda.PandaLinkState.TwistLinear) + int total_size = 0; + + if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) { // All required fields are present. + // required float twistLinearX = 1; + total_size += 1 + 4; + + // required float twistLinearY = 2; + total_size += 1 + 4; + + // required float twistLinearZ = 3; + total_size += 1 + 4; + + } else { + total_size += RequiredFieldsByteSizeFallback(); + } + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PandaLinkState_TwistLinear::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:panda.PandaLinkState.TwistLinear) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + const PandaLinkState_TwistLinear* source = + ::google::protobuf::internal::DynamicCastToGenerated<const PandaLinkState_TwistLinear>( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:panda.PandaLinkState.TwistLinear) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:panda.PandaLinkState.TwistLinear) + MergeFrom(*source); + } +} + +void PandaLinkState_TwistLinear::MergeFrom(const PandaLinkState_TwistLinear& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:panda.PandaLinkState.TwistLinear) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_twistlinearx()) { + set_twistlinearx(from.twistlinearx()); + } + if (from.has_twistlineary()) { + set_twistlineary(from.twistlineary()); + } + if (from.has_twistlinearz()) { + set_twistlinearz(from.twistlinearz()); + } + } + if (from._internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); + } +} + +void PandaLinkState_TwistLinear::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:panda.PandaLinkState.TwistLinear) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PandaLinkState_TwistLinear::CopyFrom(const PandaLinkState_TwistLinear& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:panda.PandaLinkState.TwistLinear) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PandaLinkState_TwistLinear::IsInitialized() const { + if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; + + return true; +} + +void PandaLinkState_TwistLinear::Swap(PandaLinkState_TwistLinear* other) { + if (other == this) return; + InternalSwap(other); +} +void PandaLinkState_TwistLinear::InternalSwap(PandaLinkState_TwistLinear* other) { + std::swap(twistlinearx_, other->twistlinearx_); + std::swap(twistlineary_, other->twistlineary_); + std::swap(twistlinearz_, other->twistlinearz_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PandaLinkState_TwistLinear::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PandaLinkState_TwistLinear_descriptor_; + metadata.reflection = PandaLinkState_TwistLinear_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PandaLinkState_TwistAngular::kTwistAngularXFieldNumber; +const int PandaLinkState_TwistAngular::kTwistAngularYFieldNumber; +const int PandaLinkState_TwistAngular::kTwistAngularZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PandaLinkState_TwistAngular::PandaLinkState_TwistAngular() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + SharedCtor(); + // @@protoc_insertion_point(constructor:panda.PandaLinkState.TwistAngular) +} + +void PandaLinkState_TwistAngular::InitAsDefaultInstance() { +} + +PandaLinkState_TwistAngular::PandaLinkState_TwistAngular(const PandaLinkState_TwistAngular& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + SharedCtor(); + MergeFrom(from); + // @@protoc_insertion_point(copy_constructor:panda.PandaLinkState.TwistAngular) +} + +void PandaLinkState_TwistAngular::SharedCtor() { + _cached_size_ = 0; + twistangularx_ = 0; + twistangulary_ = 0; + twistangularz_ = 0; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PandaLinkState_TwistAngular::~PandaLinkState_TwistAngular() { + // @@protoc_insertion_point(destructor:panda.PandaLinkState.TwistAngular) + SharedDtor(); +} + +void PandaLinkState_TwistAngular::SharedDtor() { + if (this != default_instance_) { + } +} + +void PandaLinkState_TwistAngular::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PandaLinkState_TwistAngular::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PandaLinkState_TwistAngular_descriptor_; +} + +const PandaLinkState_TwistAngular& PandaLinkState_TwistAngular::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_linkstate_2eproto(); + return *default_instance_; +} + +PandaLinkState_TwistAngular* PandaLinkState_TwistAngular::default_instance_ = NULL; + +PandaLinkState_TwistAngular* PandaLinkState_TwistAngular::New(::google::protobuf::Arena* arena) const { + PandaLinkState_TwistAngular* n = new PandaLinkState_TwistAngular; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PandaLinkState_TwistAngular::Clear() { +// @@protoc_insertion_point(message_clear_start:panda.PandaLinkState.TwistAngular) +#if defined(__clang__) +#define ZR_HELPER_(f) \ + _Pragma("clang diagnostic push") \ + _Pragma("clang diagnostic ignored \"-Winvalid-offsetof\"") \ + __builtin_offsetof(PandaLinkState_TwistAngular, f) \ + _Pragma("clang diagnostic pop") +#else +#define ZR_HELPER_(f) reinterpret_cast<char*>(\ + &reinterpret_cast<PandaLinkState_TwistAngular*>(16)->f) +#endif + +#define ZR_(first, last) do {\ + ::memset(&first, 0,\ + ZR_HELPER_(last) - ZR_HELPER_(first) + sizeof(last));\ +} while (0) + + ZR_(twistangularx_, twistangularz_); + +#undef ZR_HELPER_ +#undef ZR_ + + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + if (_internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->Clear(); + } +} + +bool PandaLinkState_TwistAngular::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:panda.PandaLinkState.TwistAngular) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required float twistAngularX = 1; + case 1: { + if (tag == 13) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistangularx_))); + set_has_twistangularx(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(21)) goto parse_twistAngularY; + break; + } + + // required float twistAngularY = 2; + case 2: { + if (tag == 21) { + parse_twistAngularY: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistangulary_))); + set_has_twistangulary(); + } else { + goto handle_unusual; + } + if (input->ExpectTag(29)) goto parse_twistAngularZ; + break; + } + + // required float twistAngularZ = 3; + case 3: { + if (tag == 29) { + parse_twistAngularZ: + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &twistangularz_))); + set_has_twistangularz(); + } else { + goto handle_unusual; + } + if (input->ExpectAtEnd()) goto success; + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:panda.PandaLinkState.TwistAngular) + return true; +failure: + // @@protoc_insertion_point(parse_failure:panda.PandaLinkState.TwistAngular) + return false; +#undef DO_ +} + +void PandaLinkState_TwistAngular::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:panda.PandaLinkState.TwistAngular) + // required float twistAngularX = 1; + if (has_twistangularx()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->twistangularx(), output); + } + + // required float twistAngularY = 2; + if (has_twistangulary()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->twistangulary(), output); + } + + // required float twistAngularZ = 3; + if (has_twistangularz()) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->twistangularz(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:panda.PandaLinkState.TwistAngular) +} + +::google::protobuf::uint8* PandaLinkState_TwistAngular::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:panda.PandaLinkState.TwistAngular) + // required float twistAngularX = 1; + if (has_twistangularx()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->twistangularx(), target); + } + + // required float twistAngularY = 2; + if (has_twistangulary()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->twistangulary(), target); + } + + // required float twistAngularZ = 3; + if (has_twistangularz()) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->twistangularz(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:panda.PandaLinkState.TwistAngular) + return target; +} + +int PandaLinkState_TwistAngular::RequiredFieldsByteSizeFallback() const { +// @@protoc_insertion_point(required_fields_byte_size_fallback_start:panda.PandaLinkState.TwistAngular) + int total_size = 0; + + if (has_twistangularx()) { + // required float twistAngularX = 1; + total_size += 1 + 4; + } + + if (has_twistangulary()) { + // required float twistAngularY = 2; + total_size += 1 + 4; + } + + if (has_twistangularz()) { + // required float twistAngularZ = 3; + total_size += 1 + 4; + } + + return total_size; +} +int PandaLinkState_TwistAngular::ByteSize() const { +// @@protoc_insertion_point(message_byte_size_start:panda.PandaLinkState.TwistAngular) + int total_size = 0; + + if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) { // All required fields are present. + // required float twistAngularX = 1; + total_size += 1 + 4; + + // required float twistAngularY = 2; + total_size += 1 + 4; + + // required float twistAngularZ = 3; + total_size += 1 + 4; + + } else { + total_size += RequiredFieldsByteSizeFallback(); + } + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PandaLinkState_TwistAngular::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:panda.PandaLinkState.TwistAngular) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + const PandaLinkState_TwistAngular* source = + ::google::protobuf::internal::DynamicCastToGenerated<const PandaLinkState_TwistAngular>( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:panda.PandaLinkState.TwistAngular) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:panda.PandaLinkState.TwistAngular) + MergeFrom(*source); + } +} + +void PandaLinkState_TwistAngular::MergeFrom(const PandaLinkState_TwistAngular& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:panda.PandaLinkState.TwistAngular) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_twistangularx()) { + set_twistangularx(from.twistangularx()); + } + if (from.has_twistangulary()) { + set_twistangulary(from.twistangulary()); + } + if (from.has_twistangularz()) { + set_twistangularz(from.twistangularz()); + } + } + if (from._internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); + } +} + +void PandaLinkState_TwistAngular::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:panda.PandaLinkState.TwistAngular) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PandaLinkState_TwistAngular::CopyFrom(const PandaLinkState_TwistAngular& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:panda.PandaLinkState.TwistAngular) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PandaLinkState_TwistAngular::IsInitialized() const { + if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; + + return true; +} + +void PandaLinkState_TwistAngular::Swap(PandaLinkState_TwistAngular* other) { + if (other == this) return; + InternalSwap(other); +} +void PandaLinkState_TwistAngular::InternalSwap(PandaLinkState_TwistAngular* other) { + std::swap(twistangularx_, other->twistangularx_); + std::swap(twistangulary_, other->twistangulary_); + std::swap(twistangularz_, other->twistangularz_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PandaLinkState_TwistAngular::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PandaLinkState_TwistAngular_descriptor_; + metadata.reflection = PandaLinkState_TwistAngular_reflection_; + return metadata; +} + + +// ------------------------------------------------------------------- + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PandaLinkState::kNameFieldNumber; +const int PandaLinkState::kPosFieldNumber; +const int PandaLinkState::kOrientFieldNumber; +const int PandaLinkState::kTlFieldNumber; +const int PandaLinkState::kTaFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PandaLinkState::PandaLinkState() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + SharedCtor(); + // @@protoc_insertion_point(constructor:panda.PandaLinkState) +} + +void PandaLinkState::InitAsDefaultInstance() { + pos_ = const_cast< ::panda::PandaLinkState_Position*>(&::panda::PandaLinkState_Position::default_instance()); + orient_ = const_cast< ::panda::PandaLinkState_Orientation*>(&::panda::PandaLinkState_Orientation::default_instance()); + tl_ = const_cast< ::panda::PandaLinkState_TwistLinear*>(&::panda::PandaLinkState_TwistLinear::default_instance()); + ta_ = const_cast< ::panda::PandaLinkState_TwistAngular*>(&::panda::PandaLinkState_TwistAngular::default_instance()); +} + +PandaLinkState::PandaLinkState(const PandaLinkState& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + SharedCtor(); + MergeFrom(from); + // @@protoc_insertion_point(copy_constructor:panda.PandaLinkState) +} + +void PandaLinkState::SharedCtor() { + ::google::protobuf::internal::GetEmptyString(); + _cached_size_ = 0; + name_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + pos_ = NULL; + orient_ = NULL; + tl_ = NULL; + ta_ = NULL; + ::memset(_has_bits_, 0, sizeof(_has_bits_)); +} + +PandaLinkState::~PandaLinkState() { + // @@protoc_insertion_point(destructor:panda.PandaLinkState) + SharedDtor(); +} + +void PandaLinkState::SharedDtor() { + name_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != default_instance_) { + delete pos_; + delete orient_; + delete tl_; + delete ta_; + } +} + +void PandaLinkState::SetCachedSize(int size) const { + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); +} +const ::google::protobuf::Descriptor* PandaLinkState::descriptor() { + protobuf_AssignDescriptorsOnce(); + return PandaLinkState_descriptor_; +} + +const PandaLinkState& PandaLinkState::default_instance() { + if (default_instance_ == NULL) protobuf_AddDesc_linkstate_2eproto(); + return *default_instance_; +} + +PandaLinkState* PandaLinkState::default_instance_ = NULL; + +PandaLinkState* PandaLinkState::New(::google::protobuf::Arena* arena) const { + PandaLinkState* n = new PandaLinkState; + if (arena != NULL) { + arena->Own(n); + } + return n; +} + +void PandaLinkState::Clear() { +// @@protoc_insertion_point(message_clear_start:panda.PandaLinkState) + if (_has_bits_[0 / 32] & 31u) { + if (has_name()) { + name_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + if (has_pos()) { + if (pos_ != NULL) pos_->::panda::PandaLinkState_Position::Clear(); + } + if (has_orient()) { + if (orient_ != NULL) orient_->::panda::PandaLinkState_Orientation::Clear(); + } + if (has_tl()) { + if (tl_ != NULL) tl_->::panda::PandaLinkState_TwistLinear::Clear(); + } + if (has_ta()) { + if (ta_ != NULL) ta_->::panda::PandaLinkState_TwistAngular::Clear(); + } + } + ::memset(_has_bits_, 0, sizeof(_has_bits_)); + if (_internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->Clear(); + } +} + +bool PandaLinkState::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:panda.PandaLinkState) + for (;;) { + ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // required string name = 1; + case 1: { + if (tag == 10) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_name())); + ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::PARSE, + "panda.PandaLinkState.name"); + } else { + goto handle_unusual; + } + if (input->ExpectTag(18)) goto parse_pos; + break; + } + + // optional .panda.PandaLinkState.Position pos = 2; + case 2: { + if (tag == 18) { + parse_pos: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_pos())); + } else { + goto handle_unusual; + } + if (input->ExpectTag(26)) goto parse_orient; + break; + } + + // optional .panda.PandaLinkState.Orientation orient = 3; + case 3: { + if (tag == 26) { + parse_orient: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_orient())); + } else { + goto handle_unusual; + } + if (input->ExpectTag(34)) goto parse_tl; + break; + } + + // optional .panda.PandaLinkState.TwistLinear tl = 4; + case 4: { + if (tag == 34) { + parse_tl: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_tl())); + } else { + goto handle_unusual; + } + if (input->ExpectTag(42)) goto parse_ta; + break; + } + + // optional .panda.PandaLinkState.TwistAngular ta = 5; + case 5: { + if (tag == 42) { + parse_ta: + DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( + input, mutable_ta())); + } else { + goto handle_unusual; + } + if (input->ExpectAtEnd()) goto success; + break; + } + + default: { + handle_unusual: + if (tag == 0 || + ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == + ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:panda.PandaLinkState) + return true; +failure: + // @@protoc_insertion_point(parse_failure:panda.PandaLinkState) + return false; +#undef DO_ +} + +void PandaLinkState::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:panda.PandaLinkState) + // required string name = 1; + if (has_name()) { + ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::SERIALIZE, + "panda.PandaLinkState.name"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->name(), output); + } + + // optional .panda.PandaLinkState.Position pos = 2; + if (has_pos()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, *this->pos_, output); + } + + // optional .panda.PandaLinkState.Orientation orient = 3; + if (has_orient()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, *this->orient_, output); + } + + // optional .panda.PandaLinkState.TwistLinear tl = 4; + if (has_tl()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, *this->tl_, output); + } + + // optional .panda.PandaLinkState.TwistAngular ta = 5; + if (has_ta()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, *this->ta_, output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:panda.PandaLinkState) +} + +::google::protobuf::uint8* PandaLinkState::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:panda.PandaLinkState) + // required string name = 1; + if (has_name()) { + ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField( + this->name().data(), this->name().length(), + ::google::protobuf::internal::WireFormat::SERIALIZE, + "panda.PandaLinkState.name"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->name(), target); + } + + // optional .panda.PandaLinkState.Position pos = 2; + if (has_pos()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 2, *this->pos_, false, target); + } + + // optional .panda.PandaLinkState.Orientation orient = 3; + if (has_orient()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 3, *this->orient_, false, target); + } + + // optional .panda.PandaLinkState.TwistLinear tl = 4; + if (has_tl()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 4, *this->tl_, false, target); + } + + // optional .panda.PandaLinkState.TwistAngular ta = 5; + if (has_ta()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageNoVirtualToArray( + 5, *this->ta_, false, target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:panda.PandaLinkState) + return target; +} + +int PandaLinkState::ByteSize() const { +// @@protoc_insertion_point(message_byte_size_start:panda.PandaLinkState) + int total_size = 0; + + // required string name = 1; + if (has_name()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->name()); + } + if (_has_bits_[1 / 32] & 30u) { + // optional .panda.PandaLinkState.Position pos = 2; + if (has_pos()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->pos_); + } + + // optional .panda.PandaLinkState.Orientation orient = 3; + if (has_orient()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->orient_); + } + + // optional .panda.PandaLinkState.TwistLinear tl = 4; + if (has_tl()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->tl_); + } + + // optional .panda.PandaLinkState.TwistAngular ta = 5; + if (has_ta()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( + *this->ta_); + } + + } + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + unknown_fields()); + } + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _cached_size_ = total_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + return total_size; +} + +void PandaLinkState::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:panda.PandaLinkState) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + const PandaLinkState* source = + ::google::protobuf::internal::DynamicCastToGenerated<const PandaLinkState>( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:panda.PandaLinkState) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:panda.PandaLinkState) + MergeFrom(*source); + } +} + +void PandaLinkState::MergeFrom(const PandaLinkState& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:panda.PandaLinkState) + if (GOOGLE_PREDICT_FALSE(&from == this)) { + ::google::protobuf::internal::MergeFromFail(__FILE__, __LINE__); + } + if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { + if (from.has_name()) { + set_has_name(); + name_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.name_); + } + if (from.has_pos()) { + mutable_pos()->::panda::PandaLinkState_Position::MergeFrom(from.pos()); + } + if (from.has_orient()) { + mutable_orient()->::panda::PandaLinkState_Orientation::MergeFrom(from.orient()); + } + if (from.has_tl()) { + mutable_tl()->::panda::PandaLinkState_TwistLinear::MergeFrom(from.tl()); + } + if (from.has_ta()) { + mutable_ta()->::panda::PandaLinkState_TwistAngular::MergeFrom(from.ta()); + } + } + if (from._internal_metadata_.have_unknown_fields()) { + mutable_unknown_fields()->MergeFrom(from.unknown_fields()); + } +} + +void PandaLinkState::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:panda.PandaLinkState) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PandaLinkState::CopyFrom(const PandaLinkState& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:panda.PandaLinkState) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PandaLinkState::IsInitialized() const { + if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; + + if (has_pos()) { + if (!this->pos_->IsInitialized()) return false; + } + if (has_orient()) { + if (!this->orient_->IsInitialized()) return false; + } + if (has_tl()) { + if (!this->tl_->IsInitialized()) return false; + } + if (has_ta()) { + if (!this->ta_->IsInitialized()) return false; + } + return true; +} + +void PandaLinkState::Swap(PandaLinkState* other) { + if (other == this) return; + InternalSwap(other); +} +void PandaLinkState::InternalSwap(PandaLinkState* other) { + name_.Swap(&other->name_); + std::swap(pos_, other->pos_); + std::swap(orient_, other->orient_); + std::swap(tl_, other->tl_); + std::swap(ta_, other->ta_); + std::swap(_has_bits_[0], other->_has_bits_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); + std::swap(_cached_size_, other->_cached_size_); +} + +::google::protobuf::Metadata PandaLinkState::GetMetadata() const { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::Metadata metadata; + metadata.descriptor = PandaLinkState_descriptor_; + metadata.reflection = PandaLinkState_reflection_; + return metadata; +} + +#if PROTOBUF_INLINE_NOT_IN_HEADERS +// PandaLinkState_Position + +// required float positionX = 1; +bool PandaLinkState_Position::has_positionx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +void PandaLinkState_Position::set_has_positionx() { + _has_bits_[0] |= 0x00000001u; +} +void PandaLinkState_Position::clear_has_positionx() { + _has_bits_[0] &= ~0x00000001u; +} +void PandaLinkState_Position::clear_positionx() { + positionx_ = 0; + clear_has_positionx(); +} + float PandaLinkState_Position::positionx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionX) + return positionx_; +} + void PandaLinkState_Position::set_positionx(float value) { + set_has_positionx(); + positionx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionX) +} + +// required float positionY = 2; +bool PandaLinkState_Position::has_positiony() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +void PandaLinkState_Position::set_has_positiony() { + _has_bits_[0] |= 0x00000002u; +} +void PandaLinkState_Position::clear_has_positiony() { + _has_bits_[0] &= ~0x00000002u; +} +void PandaLinkState_Position::clear_positiony() { + positiony_ = 0; + clear_has_positiony(); +} + float PandaLinkState_Position::positiony() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionY) + return positiony_; +} + void PandaLinkState_Position::set_positiony(float value) { + set_has_positiony(); + positiony_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionY) +} + +// required float positionZ = 3; +bool PandaLinkState_Position::has_positionz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +void PandaLinkState_Position::set_has_positionz() { + _has_bits_[0] |= 0x00000004u; +} +void PandaLinkState_Position::clear_has_positionz() { + _has_bits_[0] &= ~0x00000004u; +} +void PandaLinkState_Position::clear_positionz() { + positionz_ = 0; + clear_has_positionz(); +} + float PandaLinkState_Position::positionz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionZ) + return positionz_; +} + void PandaLinkState_Position::set_positionz(float value) { + set_has_positionz(); + positionz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_Orientation + +// required float orientationX = 1; +bool PandaLinkState_Orientation::has_orientationx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +void PandaLinkState_Orientation::set_has_orientationx() { + _has_bits_[0] |= 0x00000001u; +} +void PandaLinkState_Orientation::clear_has_orientationx() { + _has_bits_[0] &= ~0x00000001u; +} +void PandaLinkState_Orientation::clear_orientationx() { + orientationx_ = 0; + clear_has_orientationx(); +} + float PandaLinkState_Orientation::orientationx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationX) + return orientationx_; +} + void PandaLinkState_Orientation::set_orientationx(float value) { + set_has_orientationx(); + orientationx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationX) +} + +// required float orientationY = 2; +bool PandaLinkState_Orientation::has_orientationy() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +void PandaLinkState_Orientation::set_has_orientationy() { + _has_bits_[0] |= 0x00000002u; +} +void PandaLinkState_Orientation::clear_has_orientationy() { + _has_bits_[0] &= ~0x00000002u; +} +void PandaLinkState_Orientation::clear_orientationy() { + orientationy_ = 0; + clear_has_orientationy(); +} + float PandaLinkState_Orientation::orientationy() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationY) + return orientationy_; +} + void PandaLinkState_Orientation::set_orientationy(float value) { + set_has_orientationy(); + orientationy_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationY) +} + +// required float orientationZ = 3; +bool PandaLinkState_Orientation::has_orientationz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +void PandaLinkState_Orientation::set_has_orientationz() { + _has_bits_[0] |= 0x00000004u; +} +void PandaLinkState_Orientation::clear_has_orientationz() { + _has_bits_[0] &= ~0x00000004u; +} +void PandaLinkState_Orientation::clear_orientationz() { + orientationz_ = 0; + clear_has_orientationz(); +} + float PandaLinkState_Orientation::orientationz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationZ) + return orientationz_; +} + void PandaLinkState_Orientation::set_orientationz(float value) { + set_has_orientationz(); + orientationz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationZ) +} + +// required float orientationW = 4; +bool PandaLinkState_Orientation::has_orientationw() const { + return (_has_bits_[0] & 0x00000008u) != 0; +} +void PandaLinkState_Orientation::set_has_orientationw() { + _has_bits_[0] |= 0x00000008u; +} +void PandaLinkState_Orientation::clear_has_orientationw() { + _has_bits_[0] &= ~0x00000008u; +} +void PandaLinkState_Orientation::clear_orientationw() { + orientationw_ = 0; + clear_has_orientationw(); +} + float PandaLinkState_Orientation::orientationw() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationW) + return orientationw_; +} + void PandaLinkState_Orientation::set_orientationw(float value) { + set_has_orientationw(); + orientationw_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationW) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_TwistLinear + +// required float twistLinearX = 1; +bool PandaLinkState_TwistLinear::has_twistlinearx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +void PandaLinkState_TwistLinear::set_has_twistlinearx() { + _has_bits_[0] |= 0x00000001u; +} +void PandaLinkState_TwistLinear::clear_has_twistlinearx() { + _has_bits_[0] &= ~0x00000001u; +} +void PandaLinkState_TwistLinear::clear_twistlinearx() { + twistlinearx_ = 0; + clear_has_twistlinearx(); +} + float PandaLinkState_TwistLinear::twistlinearx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearX) + return twistlinearx_; +} + void PandaLinkState_TwistLinear::set_twistlinearx(float value) { + set_has_twistlinearx(); + twistlinearx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearX) +} + +// required float twistLinearY = 2; +bool PandaLinkState_TwistLinear::has_twistlineary() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +void PandaLinkState_TwistLinear::set_has_twistlineary() { + _has_bits_[0] |= 0x00000002u; +} +void PandaLinkState_TwistLinear::clear_has_twistlineary() { + _has_bits_[0] &= ~0x00000002u; +} +void PandaLinkState_TwistLinear::clear_twistlineary() { + twistlineary_ = 0; + clear_has_twistlineary(); +} + float PandaLinkState_TwistLinear::twistlineary() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearY) + return twistlineary_; +} + void PandaLinkState_TwistLinear::set_twistlineary(float value) { + set_has_twistlineary(); + twistlineary_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearY) +} + +// required float twistLinearZ = 3; +bool PandaLinkState_TwistLinear::has_twistlinearz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +void PandaLinkState_TwistLinear::set_has_twistlinearz() { + _has_bits_[0] |= 0x00000004u; +} +void PandaLinkState_TwistLinear::clear_has_twistlinearz() { + _has_bits_[0] &= ~0x00000004u; +} +void PandaLinkState_TwistLinear::clear_twistlinearz() { + twistlinearz_ = 0; + clear_has_twistlinearz(); +} + float PandaLinkState_TwistLinear::twistlinearz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearZ) + return twistlinearz_; +} + void PandaLinkState_TwistLinear::set_twistlinearz(float value) { + set_has_twistlinearz(); + twistlinearz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_TwistAngular + +// required float twistAngularX = 1; +bool PandaLinkState_TwistAngular::has_twistangularx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +void PandaLinkState_TwistAngular::set_has_twistangularx() { + _has_bits_[0] |= 0x00000001u; +} +void PandaLinkState_TwistAngular::clear_has_twistangularx() { + _has_bits_[0] &= ~0x00000001u; +} +void PandaLinkState_TwistAngular::clear_twistangularx() { + twistangularx_ = 0; + clear_has_twistangularx(); +} + float PandaLinkState_TwistAngular::twistangularx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularX) + return twistangularx_; +} + void PandaLinkState_TwistAngular::set_twistangularx(float value) { + set_has_twistangularx(); + twistangularx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularX) +} + +// required float twistAngularY = 2; +bool PandaLinkState_TwistAngular::has_twistangulary() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +void PandaLinkState_TwistAngular::set_has_twistangulary() { + _has_bits_[0] |= 0x00000002u; +} +void PandaLinkState_TwistAngular::clear_has_twistangulary() { + _has_bits_[0] &= ~0x00000002u; +} +void PandaLinkState_TwistAngular::clear_twistangulary() { + twistangulary_ = 0; + clear_has_twistangulary(); +} + float PandaLinkState_TwistAngular::twistangulary() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularY) + return twistangulary_; +} + void PandaLinkState_TwistAngular::set_twistangulary(float value) { + set_has_twistangulary(); + twistangulary_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularY) +} + +// required float twistAngularZ = 3; +bool PandaLinkState_TwistAngular::has_twistangularz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +void PandaLinkState_TwistAngular::set_has_twistangularz() { + _has_bits_[0] |= 0x00000004u; +} +void PandaLinkState_TwistAngular::clear_has_twistangularz() { + _has_bits_[0] &= ~0x00000004u; +} +void PandaLinkState_TwistAngular::clear_twistangularz() { + twistangularz_ = 0; + clear_has_twistangularz(); +} + float PandaLinkState_TwistAngular::twistangularz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularZ) + return twistangularz_; +} + void PandaLinkState_TwistAngular::set_twistangularz(float value) { + set_has_twistangularz(); + twistangularz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState + +// required string name = 1; +bool PandaLinkState::has_name() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +void PandaLinkState::set_has_name() { + _has_bits_[0] |= 0x00000001u; +} +void PandaLinkState::clear_has_name() { + _has_bits_[0] &= ~0x00000001u; +} +void PandaLinkState::clear_name() { + name_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_name(); +} + const ::std::string& PandaLinkState::name() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.name) + return name_.GetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + void PandaLinkState::set_name(const ::std::string& value) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:panda.PandaLinkState.name) +} + void PandaLinkState::set_name(const char* value) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:panda.PandaLinkState.name) +} + void PandaLinkState::set_name(const char* value, size_t size) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast<const char*>(value), size)); + // @@protoc_insertion_point(field_set_pointer:panda.PandaLinkState.name) +} + ::std::string* PandaLinkState::mutable_name() { + set_has_name(); + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.name) + return name_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + ::std::string* PandaLinkState::release_name() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.name) + clear_has_name(); + return name_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + void PandaLinkState::set_allocated_name(::std::string* name) { + if (name != NULL) { + set_has_name(); + } else { + clear_has_name(); + } + name_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), name); + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.name) +} + +// optional .panda.PandaLinkState.Position pos = 2; +bool PandaLinkState::has_pos() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +void PandaLinkState::set_has_pos() { + _has_bits_[0] |= 0x00000002u; +} +void PandaLinkState::clear_has_pos() { + _has_bits_[0] &= ~0x00000002u; +} +void PandaLinkState::clear_pos() { + if (pos_ != NULL) pos_->::panda::PandaLinkState_Position::Clear(); + clear_has_pos(); +} +const ::panda::PandaLinkState_Position& PandaLinkState::pos() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.pos) + return pos_ != NULL ? *pos_ : *default_instance_->pos_; +} +::panda::PandaLinkState_Position* PandaLinkState::mutable_pos() { + set_has_pos(); + if (pos_ == NULL) { + pos_ = new ::panda::PandaLinkState_Position; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.pos) + return pos_; +} +::panda::PandaLinkState_Position* PandaLinkState::release_pos() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.pos) + clear_has_pos(); + ::panda::PandaLinkState_Position* temp = pos_; + pos_ = NULL; + return temp; +} +void PandaLinkState::set_allocated_pos(::panda::PandaLinkState_Position* pos) { + delete pos_; + pos_ = pos; + if (pos) { + set_has_pos(); + } else { + clear_has_pos(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.pos) +} + +// optional .panda.PandaLinkState.Orientation orient = 3; +bool PandaLinkState::has_orient() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +void PandaLinkState::set_has_orient() { + _has_bits_[0] |= 0x00000004u; +} +void PandaLinkState::clear_has_orient() { + _has_bits_[0] &= ~0x00000004u; +} +void PandaLinkState::clear_orient() { + if (orient_ != NULL) orient_->::panda::PandaLinkState_Orientation::Clear(); + clear_has_orient(); +} +const ::panda::PandaLinkState_Orientation& PandaLinkState::orient() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.orient) + return orient_ != NULL ? *orient_ : *default_instance_->orient_; +} +::panda::PandaLinkState_Orientation* PandaLinkState::mutable_orient() { + set_has_orient(); + if (orient_ == NULL) { + orient_ = new ::panda::PandaLinkState_Orientation; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.orient) + return orient_; +} +::panda::PandaLinkState_Orientation* PandaLinkState::release_orient() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.orient) + clear_has_orient(); + ::panda::PandaLinkState_Orientation* temp = orient_; + orient_ = NULL; + return temp; +} +void PandaLinkState::set_allocated_orient(::panda::PandaLinkState_Orientation* orient) { + delete orient_; + orient_ = orient; + if (orient) { + set_has_orient(); + } else { + clear_has_orient(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.orient) +} + +// optional .panda.PandaLinkState.TwistLinear tl = 4; +bool PandaLinkState::has_tl() const { + return (_has_bits_[0] & 0x00000008u) != 0; +} +void PandaLinkState::set_has_tl() { + _has_bits_[0] |= 0x00000008u; +} +void PandaLinkState::clear_has_tl() { + _has_bits_[0] &= ~0x00000008u; +} +void PandaLinkState::clear_tl() { + if (tl_ != NULL) tl_->::panda::PandaLinkState_TwistLinear::Clear(); + clear_has_tl(); +} +const ::panda::PandaLinkState_TwistLinear& PandaLinkState::tl() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.tl) + return tl_ != NULL ? *tl_ : *default_instance_->tl_; +} +::panda::PandaLinkState_TwistLinear* PandaLinkState::mutable_tl() { + set_has_tl(); + if (tl_ == NULL) { + tl_ = new ::panda::PandaLinkState_TwistLinear; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.tl) + return tl_; +} +::panda::PandaLinkState_TwistLinear* PandaLinkState::release_tl() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.tl) + clear_has_tl(); + ::panda::PandaLinkState_TwistLinear* temp = tl_; + tl_ = NULL; + return temp; +} +void PandaLinkState::set_allocated_tl(::panda::PandaLinkState_TwistLinear* tl) { + delete tl_; + tl_ = tl; + if (tl) { + set_has_tl(); + } else { + clear_has_tl(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.tl) +} + +// optional .panda.PandaLinkState.TwistAngular ta = 5; +bool PandaLinkState::has_ta() const { + return (_has_bits_[0] & 0x00000010u) != 0; +} +void PandaLinkState::set_has_ta() { + _has_bits_[0] |= 0x00000010u; +} +void PandaLinkState::clear_has_ta() { + _has_bits_[0] &= ~0x00000010u; +} +void PandaLinkState::clear_ta() { + if (ta_ != NULL) ta_->::panda::PandaLinkState_TwistAngular::Clear(); + clear_has_ta(); +} +const ::panda::PandaLinkState_TwistAngular& PandaLinkState::ta() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.ta) + return ta_ != NULL ? *ta_ : *default_instance_->ta_; +} +::panda::PandaLinkState_TwistAngular* PandaLinkState::mutable_ta() { + set_has_ta(); + if (ta_ == NULL) { + ta_ = new ::panda::PandaLinkState_TwistAngular; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.ta) + return ta_; +} +::panda::PandaLinkState_TwistAngular* PandaLinkState::release_ta() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.ta) + clear_has_ta(); + ::panda::PandaLinkState_TwistAngular* temp = ta_; + ta_ = NULL; + return temp; +} +void PandaLinkState::set_allocated_ta(::panda::PandaLinkState_TwistAngular* ta) { + delete ta_; + ta_ = ta; + if (ta) { + set_has_ta(); + } else { + clear_has_ta(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.ta) +} + +#endif // PROTOBUF_INLINE_NOT_IN_HEADERS + +// @@protoc_insertion_point(namespace_scope) + +} // namespace panda + +// @@protoc_insertion_point(global_scope) diff --git a/src/messages/linkstate.pb.h b/src/messages/linkstate.pb.h new file mode 100644 index 0000000000000000000000000000000000000000..2ebd4a0449e4326685d0c626229161e41be5d276 --- /dev/null +++ b/src/messages/linkstate.pb.h @@ -0,0 +1,1252 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: linkstate.proto + +#ifndef PROTOBUF_linkstate_2eproto__INCLUDED +#define PROTOBUF_linkstate_2eproto__INCLUDED + +#include <string> + +#include <google/protobuf/stubs/common.h> + +#if GOOGLE_PROTOBUF_VERSION < 3000000 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3000000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include <google/protobuf/arena.h> +#include <google/protobuf/arenastring.h> +#include <google/protobuf/generated_message_util.h> +#include <google/protobuf/metadata.h> +#include <google/protobuf/message.h> +#include <google/protobuf/repeated_field.h> +#include <google/protobuf/extension_set.h> +#include <google/protobuf/unknown_field_set.h> +// @@protoc_insertion_point(includes) + +namespace panda { + +// Internal implementation detail -- do not call these. +void protobuf_AddDesc_linkstate_2eproto(); +void protobuf_AssignDesc_linkstate_2eproto(); +void protobuf_ShutdownFile_linkstate_2eproto(); + +class PandaLinkState; +class PandaLinkState_Orientation; +class PandaLinkState_Position; +class PandaLinkState_TwistAngular; +class PandaLinkState_TwistLinear; + +// =================================================================== + +class PandaLinkState_Position : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:panda.PandaLinkState.Position) */ { + public: + PandaLinkState_Position(); + virtual ~PandaLinkState_Position(); + + PandaLinkState_Position(const PandaLinkState_Position& from); + + inline PandaLinkState_Position& operator=(const PandaLinkState_Position& from) { + CopyFrom(from); + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields(); + } + + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields(); + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PandaLinkState_Position& default_instance(); + + void Swap(PandaLinkState_Position* other); + + // implements Message ---------------------------------------------- + + inline PandaLinkState_Position* New() const { return New(NULL); } + + PandaLinkState_Position* New(::google::protobuf::Arena* arena) const; + void CopyFrom(const ::google::protobuf::Message& from); + void MergeFrom(const ::google::protobuf::Message& from); + void CopyFrom(const PandaLinkState_Position& from); + void MergeFrom(const PandaLinkState_Position& from); + void Clear(); + bool IsInitialized() const; + + int ByteSize() const; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input); + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* output) const; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const { + return InternalSerializeWithCachedSizesToArray(false, output); + } + int GetCachedSize() const { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const; + void InternalSwap(PandaLinkState_Position* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return _internal_metadata_.arena(); + } + inline void* MaybeArenaPtr() const { + return _internal_metadata_.raw_arena_ptr(); + } + public: + + ::google::protobuf::Metadata GetMetadata() const; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // required float positionX = 1; + bool has_positionx() const; + void clear_positionx(); + static const int kPositionXFieldNumber = 1; + float positionx() const; + void set_positionx(float value); + + // required float positionY = 2; + bool has_positiony() const; + void clear_positiony(); + static const int kPositionYFieldNumber = 2; + float positiony() const; + void set_positiony(float value); + + // required float positionZ = 3; + bool has_positionz() const; + void clear_positionz(); + static const int kPositionZFieldNumber = 3; + float positionz() const; + void set_positionz(float value); + + // @@protoc_insertion_point(class_scope:panda.PandaLinkState.Position) + private: + inline void set_has_positionx(); + inline void clear_has_positionx(); + inline void set_has_positiony(); + inline void clear_has_positiony(); + inline void set_has_positionz(); + inline void clear_has_positionz(); + + // helper for ByteSize() + int RequiredFieldsByteSizeFallback() const; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 _has_bits_[1]; + mutable int _cached_size_; + float positionx_; + float positiony_; + float positionz_; + friend void protobuf_AddDesc_linkstate_2eproto(); + friend void protobuf_AssignDesc_linkstate_2eproto(); + friend void protobuf_ShutdownFile_linkstate_2eproto(); + + void InitAsDefaultInstance(); + static PandaLinkState_Position* default_instance_; +}; +// ------------------------------------------------------------------- + +class PandaLinkState_Orientation : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:panda.PandaLinkState.Orientation) */ { + public: + PandaLinkState_Orientation(); + virtual ~PandaLinkState_Orientation(); + + PandaLinkState_Orientation(const PandaLinkState_Orientation& from); + + inline PandaLinkState_Orientation& operator=(const PandaLinkState_Orientation& from) { + CopyFrom(from); + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields(); + } + + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields(); + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PandaLinkState_Orientation& default_instance(); + + void Swap(PandaLinkState_Orientation* other); + + // implements Message ---------------------------------------------- + + inline PandaLinkState_Orientation* New() const { return New(NULL); } + + PandaLinkState_Orientation* New(::google::protobuf::Arena* arena) const; + void CopyFrom(const ::google::protobuf::Message& from); + void MergeFrom(const ::google::protobuf::Message& from); + void CopyFrom(const PandaLinkState_Orientation& from); + void MergeFrom(const PandaLinkState_Orientation& from); + void Clear(); + bool IsInitialized() const; + + int ByteSize() const; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input); + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* output) const; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const { + return InternalSerializeWithCachedSizesToArray(false, output); + } + int GetCachedSize() const { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const; + void InternalSwap(PandaLinkState_Orientation* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return _internal_metadata_.arena(); + } + inline void* MaybeArenaPtr() const { + return _internal_metadata_.raw_arena_ptr(); + } + public: + + ::google::protobuf::Metadata GetMetadata() const; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // required float orientationX = 1; + bool has_orientationx() const; + void clear_orientationx(); + static const int kOrientationXFieldNumber = 1; + float orientationx() const; + void set_orientationx(float value); + + // required float orientationY = 2; + bool has_orientationy() const; + void clear_orientationy(); + static const int kOrientationYFieldNumber = 2; + float orientationy() const; + void set_orientationy(float value); + + // required float orientationZ = 3; + bool has_orientationz() const; + void clear_orientationz(); + static const int kOrientationZFieldNumber = 3; + float orientationz() const; + void set_orientationz(float value); + + // required float orientationW = 4; + bool has_orientationw() const; + void clear_orientationw(); + static const int kOrientationWFieldNumber = 4; + float orientationw() const; + void set_orientationw(float value); + + // @@protoc_insertion_point(class_scope:panda.PandaLinkState.Orientation) + private: + inline void set_has_orientationx(); + inline void clear_has_orientationx(); + inline void set_has_orientationy(); + inline void clear_has_orientationy(); + inline void set_has_orientationz(); + inline void clear_has_orientationz(); + inline void set_has_orientationw(); + inline void clear_has_orientationw(); + + // helper for ByteSize() + int RequiredFieldsByteSizeFallback() const; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 _has_bits_[1]; + mutable int _cached_size_; + float orientationx_; + float orientationy_; + float orientationz_; + float orientationw_; + friend void protobuf_AddDesc_linkstate_2eproto(); + friend void protobuf_AssignDesc_linkstate_2eproto(); + friend void protobuf_ShutdownFile_linkstate_2eproto(); + + void InitAsDefaultInstance(); + static PandaLinkState_Orientation* default_instance_; +}; +// ------------------------------------------------------------------- + +class PandaLinkState_TwistLinear : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:panda.PandaLinkState.TwistLinear) */ { + public: + PandaLinkState_TwistLinear(); + virtual ~PandaLinkState_TwistLinear(); + + PandaLinkState_TwistLinear(const PandaLinkState_TwistLinear& from); + + inline PandaLinkState_TwistLinear& operator=(const PandaLinkState_TwistLinear& from) { + CopyFrom(from); + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields(); + } + + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields(); + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PandaLinkState_TwistLinear& default_instance(); + + void Swap(PandaLinkState_TwistLinear* other); + + // implements Message ---------------------------------------------- + + inline PandaLinkState_TwistLinear* New() const { return New(NULL); } + + PandaLinkState_TwistLinear* New(::google::protobuf::Arena* arena) const; + void CopyFrom(const ::google::protobuf::Message& from); + void MergeFrom(const ::google::protobuf::Message& from); + void CopyFrom(const PandaLinkState_TwistLinear& from); + void MergeFrom(const PandaLinkState_TwistLinear& from); + void Clear(); + bool IsInitialized() const; + + int ByteSize() const; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input); + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* output) const; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const { + return InternalSerializeWithCachedSizesToArray(false, output); + } + int GetCachedSize() const { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const; + void InternalSwap(PandaLinkState_TwistLinear* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return _internal_metadata_.arena(); + } + inline void* MaybeArenaPtr() const { + return _internal_metadata_.raw_arena_ptr(); + } + public: + + ::google::protobuf::Metadata GetMetadata() const; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // required float twistLinearX = 1; + bool has_twistlinearx() const; + void clear_twistlinearx(); + static const int kTwistLinearXFieldNumber = 1; + float twistlinearx() const; + void set_twistlinearx(float value); + + // required float twistLinearY = 2; + bool has_twistlineary() const; + void clear_twistlineary(); + static const int kTwistLinearYFieldNumber = 2; + float twistlineary() const; + void set_twistlineary(float value); + + // required float twistLinearZ = 3; + bool has_twistlinearz() const; + void clear_twistlinearz(); + static const int kTwistLinearZFieldNumber = 3; + float twistlinearz() const; + void set_twistlinearz(float value); + + // @@protoc_insertion_point(class_scope:panda.PandaLinkState.TwistLinear) + private: + inline void set_has_twistlinearx(); + inline void clear_has_twistlinearx(); + inline void set_has_twistlineary(); + inline void clear_has_twistlineary(); + inline void set_has_twistlinearz(); + inline void clear_has_twistlinearz(); + + // helper for ByteSize() + int RequiredFieldsByteSizeFallback() const; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 _has_bits_[1]; + mutable int _cached_size_; + float twistlinearx_; + float twistlineary_; + float twistlinearz_; + friend void protobuf_AddDesc_linkstate_2eproto(); + friend void protobuf_AssignDesc_linkstate_2eproto(); + friend void protobuf_ShutdownFile_linkstate_2eproto(); + + void InitAsDefaultInstance(); + static PandaLinkState_TwistLinear* default_instance_; +}; +// ------------------------------------------------------------------- + +class PandaLinkState_TwistAngular : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:panda.PandaLinkState.TwistAngular) */ { + public: + PandaLinkState_TwistAngular(); + virtual ~PandaLinkState_TwistAngular(); + + PandaLinkState_TwistAngular(const PandaLinkState_TwistAngular& from); + + inline PandaLinkState_TwistAngular& operator=(const PandaLinkState_TwistAngular& from) { + CopyFrom(from); + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields(); + } + + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields(); + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PandaLinkState_TwistAngular& default_instance(); + + void Swap(PandaLinkState_TwistAngular* other); + + // implements Message ---------------------------------------------- + + inline PandaLinkState_TwistAngular* New() const { return New(NULL); } + + PandaLinkState_TwistAngular* New(::google::protobuf::Arena* arena) const; + void CopyFrom(const ::google::protobuf::Message& from); + void MergeFrom(const ::google::protobuf::Message& from); + void CopyFrom(const PandaLinkState_TwistAngular& from); + void MergeFrom(const PandaLinkState_TwistAngular& from); + void Clear(); + bool IsInitialized() const; + + int ByteSize() const; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input); + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* output) const; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const { + return InternalSerializeWithCachedSizesToArray(false, output); + } + int GetCachedSize() const { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const; + void InternalSwap(PandaLinkState_TwistAngular* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return _internal_metadata_.arena(); + } + inline void* MaybeArenaPtr() const { + return _internal_metadata_.raw_arena_ptr(); + } + public: + + ::google::protobuf::Metadata GetMetadata() const; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // required float twistAngularX = 1; + bool has_twistangularx() const; + void clear_twistangularx(); + static const int kTwistAngularXFieldNumber = 1; + float twistangularx() const; + void set_twistangularx(float value); + + // required float twistAngularY = 2; + bool has_twistangulary() const; + void clear_twistangulary(); + static const int kTwistAngularYFieldNumber = 2; + float twistangulary() const; + void set_twistangulary(float value); + + // required float twistAngularZ = 3; + bool has_twistangularz() const; + void clear_twistangularz(); + static const int kTwistAngularZFieldNumber = 3; + float twistangularz() const; + void set_twistangularz(float value); + + // @@protoc_insertion_point(class_scope:panda.PandaLinkState.TwistAngular) + private: + inline void set_has_twistangularx(); + inline void clear_has_twistangularx(); + inline void set_has_twistangulary(); + inline void clear_has_twistangulary(); + inline void set_has_twistangularz(); + inline void clear_has_twistangularz(); + + // helper for ByteSize() + int RequiredFieldsByteSizeFallback() const; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 _has_bits_[1]; + mutable int _cached_size_; + float twistangularx_; + float twistangulary_; + float twistangularz_; + friend void protobuf_AddDesc_linkstate_2eproto(); + friend void protobuf_AssignDesc_linkstate_2eproto(); + friend void protobuf_ShutdownFile_linkstate_2eproto(); + + void InitAsDefaultInstance(); + static PandaLinkState_TwistAngular* default_instance_; +}; +// ------------------------------------------------------------------- + +class PandaLinkState : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:panda.PandaLinkState) */ { + public: + PandaLinkState(); + virtual ~PandaLinkState(); + + PandaLinkState(const PandaLinkState& from); + + inline PandaLinkState& operator=(const PandaLinkState& from) { + CopyFrom(from); + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { + return _internal_metadata_.unknown_fields(); + } + + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { + return _internal_metadata_.mutable_unknown_fields(); + } + + static const ::google::protobuf::Descriptor* descriptor(); + static const PandaLinkState& default_instance(); + + void Swap(PandaLinkState* other); + + // implements Message ---------------------------------------------- + + inline PandaLinkState* New() const { return New(NULL); } + + PandaLinkState* New(::google::protobuf::Arena* arena) const; + void CopyFrom(const ::google::protobuf::Message& from); + void MergeFrom(const ::google::protobuf::Message& from); + void CopyFrom(const PandaLinkState& from); + void MergeFrom(const PandaLinkState& from); + void Clear(); + bool IsInitialized() const; + + int ByteSize() const; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input); + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* output) const; + ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const { + return InternalSerializeWithCachedSizesToArray(false, output); + } + int GetCachedSize() const { return _cached_size_; } + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const; + void InternalSwap(PandaLinkState* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return _internal_metadata_.arena(); + } + inline void* MaybeArenaPtr() const { + return _internal_metadata_.raw_arena_ptr(); + } + public: + + ::google::protobuf::Metadata GetMetadata() const; + + // nested types ---------------------------------------------------- + + typedef PandaLinkState_Position Position; + typedef PandaLinkState_Orientation Orientation; + typedef PandaLinkState_TwistLinear TwistLinear; + typedef PandaLinkState_TwistAngular TwistAngular; + + // accessors ------------------------------------------------------- + + // required string name = 1; + bool has_name() const; + void clear_name(); + static const int kNameFieldNumber = 1; + const ::std::string& name() const; + void set_name(const ::std::string& value); + void set_name(const char* value); + void set_name(const char* value, size_t size); + ::std::string* mutable_name(); + ::std::string* release_name(); + void set_allocated_name(::std::string* name); + + // optional .panda.PandaLinkState.Position pos = 2; + bool has_pos() const; + void clear_pos(); + static const int kPosFieldNumber = 2; + const ::panda::PandaLinkState_Position& pos() const; + ::panda::PandaLinkState_Position* mutable_pos(); + ::panda::PandaLinkState_Position* release_pos(); + void set_allocated_pos(::panda::PandaLinkState_Position* pos); + + // optional .panda.PandaLinkState.Orientation orient = 3; + bool has_orient() const; + void clear_orient(); + static const int kOrientFieldNumber = 3; + const ::panda::PandaLinkState_Orientation& orient() const; + ::panda::PandaLinkState_Orientation* mutable_orient(); + ::panda::PandaLinkState_Orientation* release_orient(); + void set_allocated_orient(::panda::PandaLinkState_Orientation* orient); + + // optional .panda.PandaLinkState.TwistLinear tl = 4; + bool has_tl() const; + void clear_tl(); + static const int kTlFieldNumber = 4; + const ::panda::PandaLinkState_TwistLinear& tl() const; + ::panda::PandaLinkState_TwistLinear* mutable_tl(); + ::panda::PandaLinkState_TwistLinear* release_tl(); + void set_allocated_tl(::panda::PandaLinkState_TwistLinear* tl); + + // optional .panda.PandaLinkState.TwistAngular ta = 5; + bool has_ta() const; + void clear_ta(); + static const int kTaFieldNumber = 5; + const ::panda::PandaLinkState_TwistAngular& ta() const; + ::panda::PandaLinkState_TwistAngular* mutable_ta(); + ::panda::PandaLinkState_TwistAngular* release_ta(); + void set_allocated_ta(::panda::PandaLinkState_TwistAngular* ta); + + // @@protoc_insertion_point(class_scope:panda.PandaLinkState) + private: + inline void set_has_name(); + inline void clear_has_name(); + inline void set_has_pos(); + inline void clear_has_pos(); + inline void set_has_orient(); + inline void clear_has_orient(); + inline void set_has_tl(); + inline void clear_has_tl(); + inline void set_has_ta(); + inline void clear_has_ta(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 _has_bits_[1]; + mutable int _cached_size_; + ::google::protobuf::internal::ArenaStringPtr name_; + ::panda::PandaLinkState_Position* pos_; + ::panda::PandaLinkState_Orientation* orient_; + ::panda::PandaLinkState_TwistLinear* tl_; + ::panda::PandaLinkState_TwistAngular* ta_; + friend void protobuf_AddDesc_linkstate_2eproto(); + friend void protobuf_AssignDesc_linkstate_2eproto(); + friend void protobuf_ShutdownFile_linkstate_2eproto(); + + void InitAsDefaultInstance(); + static PandaLinkState* default_instance_; +}; +// =================================================================== + + +// =================================================================== + +#if !PROTOBUF_INLINE_NOT_IN_HEADERS +// PandaLinkState_Position + +// required float positionX = 1; +inline bool PandaLinkState_Position::has_positionx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +inline void PandaLinkState_Position::set_has_positionx() { + _has_bits_[0] |= 0x00000001u; +} +inline void PandaLinkState_Position::clear_has_positionx() { + _has_bits_[0] &= ~0x00000001u; +} +inline void PandaLinkState_Position::clear_positionx() { + positionx_ = 0; + clear_has_positionx(); +} +inline float PandaLinkState_Position::positionx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionX) + return positionx_; +} +inline void PandaLinkState_Position::set_positionx(float value) { + set_has_positionx(); + positionx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionX) +} + +// required float positionY = 2; +inline bool PandaLinkState_Position::has_positiony() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +inline void PandaLinkState_Position::set_has_positiony() { + _has_bits_[0] |= 0x00000002u; +} +inline void PandaLinkState_Position::clear_has_positiony() { + _has_bits_[0] &= ~0x00000002u; +} +inline void PandaLinkState_Position::clear_positiony() { + positiony_ = 0; + clear_has_positiony(); +} +inline float PandaLinkState_Position::positiony() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionY) + return positiony_; +} +inline void PandaLinkState_Position::set_positiony(float value) { + set_has_positiony(); + positiony_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionY) +} + +// required float positionZ = 3; +inline bool PandaLinkState_Position::has_positionz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +inline void PandaLinkState_Position::set_has_positionz() { + _has_bits_[0] |= 0x00000004u; +} +inline void PandaLinkState_Position::clear_has_positionz() { + _has_bits_[0] &= ~0x00000004u; +} +inline void PandaLinkState_Position::clear_positionz() { + positionz_ = 0; + clear_has_positionz(); +} +inline float PandaLinkState_Position::positionz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Position.positionZ) + return positionz_; +} +inline void PandaLinkState_Position::set_positionz(float value) { + set_has_positionz(); + positionz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Position.positionZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_Orientation + +// required float orientationX = 1; +inline bool PandaLinkState_Orientation::has_orientationx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +inline void PandaLinkState_Orientation::set_has_orientationx() { + _has_bits_[0] |= 0x00000001u; +} +inline void PandaLinkState_Orientation::clear_has_orientationx() { + _has_bits_[0] &= ~0x00000001u; +} +inline void PandaLinkState_Orientation::clear_orientationx() { + orientationx_ = 0; + clear_has_orientationx(); +} +inline float PandaLinkState_Orientation::orientationx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationX) + return orientationx_; +} +inline void PandaLinkState_Orientation::set_orientationx(float value) { + set_has_orientationx(); + orientationx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationX) +} + +// required float orientationY = 2; +inline bool PandaLinkState_Orientation::has_orientationy() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +inline void PandaLinkState_Orientation::set_has_orientationy() { + _has_bits_[0] |= 0x00000002u; +} +inline void PandaLinkState_Orientation::clear_has_orientationy() { + _has_bits_[0] &= ~0x00000002u; +} +inline void PandaLinkState_Orientation::clear_orientationy() { + orientationy_ = 0; + clear_has_orientationy(); +} +inline float PandaLinkState_Orientation::orientationy() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationY) + return orientationy_; +} +inline void PandaLinkState_Orientation::set_orientationy(float value) { + set_has_orientationy(); + orientationy_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationY) +} + +// required float orientationZ = 3; +inline bool PandaLinkState_Orientation::has_orientationz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +inline void PandaLinkState_Orientation::set_has_orientationz() { + _has_bits_[0] |= 0x00000004u; +} +inline void PandaLinkState_Orientation::clear_has_orientationz() { + _has_bits_[0] &= ~0x00000004u; +} +inline void PandaLinkState_Orientation::clear_orientationz() { + orientationz_ = 0; + clear_has_orientationz(); +} +inline float PandaLinkState_Orientation::orientationz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationZ) + return orientationz_; +} +inline void PandaLinkState_Orientation::set_orientationz(float value) { + set_has_orientationz(); + orientationz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationZ) +} + +// required float orientationW = 4; +inline bool PandaLinkState_Orientation::has_orientationw() const { + return (_has_bits_[0] & 0x00000008u) != 0; +} +inline void PandaLinkState_Orientation::set_has_orientationw() { + _has_bits_[0] |= 0x00000008u; +} +inline void PandaLinkState_Orientation::clear_has_orientationw() { + _has_bits_[0] &= ~0x00000008u; +} +inline void PandaLinkState_Orientation::clear_orientationw() { + orientationw_ = 0; + clear_has_orientationw(); +} +inline float PandaLinkState_Orientation::orientationw() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.Orientation.orientationW) + return orientationw_; +} +inline void PandaLinkState_Orientation::set_orientationw(float value) { + set_has_orientationw(); + orientationw_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.Orientation.orientationW) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_TwistLinear + +// required float twistLinearX = 1; +inline bool PandaLinkState_TwistLinear::has_twistlinearx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +inline void PandaLinkState_TwistLinear::set_has_twistlinearx() { + _has_bits_[0] |= 0x00000001u; +} +inline void PandaLinkState_TwistLinear::clear_has_twistlinearx() { + _has_bits_[0] &= ~0x00000001u; +} +inline void PandaLinkState_TwistLinear::clear_twistlinearx() { + twistlinearx_ = 0; + clear_has_twistlinearx(); +} +inline float PandaLinkState_TwistLinear::twistlinearx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearX) + return twistlinearx_; +} +inline void PandaLinkState_TwistLinear::set_twistlinearx(float value) { + set_has_twistlinearx(); + twistlinearx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearX) +} + +// required float twistLinearY = 2; +inline bool PandaLinkState_TwistLinear::has_twistlineary() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +inline void PandaLinkState_TwistLinear::set_has_twistlineary() { + _has_bits_[0] |= 0x00000002u; +} +inline void PandaLinkState_TwistLinear::clear_has_twistlineary() { + _has_bits_[0] &= ~0x00000002u; +} +inline void PandaLinkState_TwistLinear::clear_twistlineary() { + twistlineary_ = 0; + clear_has_twistlineary(); +} +inline float PandaLinkState_TwistLinear::twistlineary() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearY) + return twistlineary_; +} +inline void PandaLinkState_TwistLinear::set_twistlineary(float value) { + set_has_twistlineary(); + twistlineary_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearY) +} + +// required float twistLinearZ = 3; +inline bool PandaLinkState_TwistLinear::has_twistlinearz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +inline void PandaLinkState_TwistLinear::set_has_twistlinearz() { + _has_bits_[0] |= 0x00000004u; +} +inline void PandaLinkState_TwistLinear::clear_has_twistlinearz() { + _has_bits_[0] &= ~0x00000004u; +} +inline void PandaLinkState_TwistLinear::clear_twistlinearz() { + twistlinearz_ = 0; + clear_has_twistlinearz(); +} +inline float PandaLinkState_TwistLinear::twistlinearz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistLinear.twistLinearZ) + return twistlinearz_; +} +inline void PandaLinkState_TwistLinear::set_twistlinearz(float value) { + set_has_twistlinearz(); + twistlinearz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistLinear.twistLinearZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState_TwistAngular + +// required float twistAngularX = 1; +inline bool PandaLinkState_TwistAngular::has_twistangularx() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +inline void PandaLinkState_TwistAngular::set_has_twistangularx() { + _has_bits_[0] |= 0x00000001u; +} +inline void PandaLinkState_TwistAngular::clear_has_twistangularx() { + _has_bits_[0] &= ~0x00000001u; +} +inline void PandaLinkState_TwistAngular::clear_twistangularx() { + twistangularx_ = 0; + clear_has_twistangularx(); +} +inline float PandaLinkState_TwistAngular::twistangularx() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularX) + return twistangularx_; +} +inline void PandaLinkState_TwistAngular::set_twistangularx(float value) { + set_has_twistangularx(); + twistangularx_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularX) +} + +// required float twistAngularY = 2; +inline bool PandaLinkState_TwistAngular::has_twistangulary() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +inline void PandaLinkState_TwistAngular::set_has_twistangulary() { + _has_bits_[0] |= 0x00000002u; +} +inline void PandaLinkState_TwistAngular::clear_has_twistangulary() { + _has_bits_[0] &= ~0x00000002u; +} +inline void PandaLinkState_TwistAngular::clear_twistangulary() { + twistangulary_ = 0; + clear_has_twistangulary(); +} +inline float PandaLinkState_TwistAngular::twistangulary() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularY) + return twistangulary_; +} +inline void PandaLinkState_TwistAngular::set_twistangulary(float value) { + set_has_twistangulary(); + twistangulary_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularY) +} + +// required float twistAngularZ = 3; +inline bool PandaLinkState_TwistAngular::has_twistangularz() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +inline void PandaLinkState_TwistAngular::set_has_twistangularz() { + _has_bits_[0] |= 0x00000004u; +} +inline void PandaLinkState_TwistAngular::clear_has_twistangularz() { + _has_bits_[0] &= ~0x00000004u; +} +inline void PandaLinkState_TwistAngular::clear_twistangularz() { + twistangularz_ = 0; + clear_has_twistangularz(); +} +inline float PandaLinkState_TwistAngular::twistangularz() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.TwistAngular.twistAngularZ) + return twistangularz_; +} +inline void PandaLinkState_TwistAngular::set_twistangularz(float value) { + set_has_twistangularz(); + twistangularz_ = value; + // @@protoc_insertion_point(field_set:panda.PandaLinkState.TwistAngular.twistAngularZ) +} + +// ------------------------------------------------------------------- + +// PandaLinkState + +// required string name = 1; +inline bool PandaLinkState::has_name() const { + return (_has_bits_[0] & 0x00000001u) != 0; +} +inline void PandaLinkState::set_has_name() { + _has_bits_[0] |= 0x00000001u; +} +inline void PandaLinkState::clear_has_name() { + _has_bits_[0] &= ~0x00000001u; +} +inline void PandaLinkState::clear_name() { + name_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_name(); +} +inline const ::std::string& PandaLinkState::name() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.name) + return name_.GetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void PandaLinkState::set_name(const ::std::string& value) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:panda.PandaLinkState.name) +} +inline void PandaLinkState::set_name(const char* value) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:panda.PandaLinkState.name) +} +inline void PandaLinkState::set_name(const char* value, size_t size) { + set_has_name(); + name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast<const char*>(value), size)); + // @@protoc_insertion_point(field_set_pointer:panda.PandaLinkState.name) +} +inline ::std::string* PandaLinkState::mutable_name() { + set_has_name(); + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.name) + return name_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* PandaLinkState::release_name() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.name) + clear_has_name(); + return name_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void PandaLinkState::set_allocated_name(::std::string* name) { + if (name != NULL) { + set_has_name(); + } else { + clear_has_name(); + } + name_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), name); + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.name) +} + +// optional .panda.PandaLinkState.Position pos = 2; +inline bool PandaLinkState::has_pos() const { + return (_has_bits_[0] & 0x00000002u) != 0; +} +inline void PandaLinkState::set_has_pos() { + _has_bits_[0] |= 0x00000002u; +} +inline void PandaLinkState::clear_has_pos() { + _has_bits_[0] &= ~0x00000002u; +} +inline void PandaLinkState::clear_pos() { + if (pos_ != NULL) pos_->::panda::PandaLinkState_Position::Clear(); + clear_has_pos(); +} +inline const ::panda::PandaLinkState_Position& PandaLinkState::pos() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.pos) + return pos_ != NULL ? *pos_ : *default_instance_->pos_; +} +inline ::panda::PandaLinkState_Position* PandaLinkState::mutable_pos() { + set_has_pos(); + if (pos_ == NULL) { + pos_ = new ::panda::PandaLinkState_Position; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.pos) + return pos_; +} +inline ::panda::PandaLinkState_Position* PandaLinkState::release_pos() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.pos) + clear_has_pos(); + ::panda::PandaLinkState_Position* temp = pos_; + pos_ = NULL; + return temp; +} +inline void PandaLinkState::set_allocated_pos(::panda::PandaLinkState_Position* pos) { + delete pos_; + pos_ = pos; + if (pos) { + set_has_pos(); + } else { + clear_has_pos(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.pos) +} + +// optional .panda.PandaLinkState.Orientation orient = 3; +inline bool PandaLinkState::has_orient() const { + return (_has_bits_[0] & 0x00000004u) != 0; +} +inline void PandaLinkState::set_has_orient() { + _has_bits_[0] |= 0x00000004u; +} +inline void PandaLinkState::clear_has_orient() { + _has_bits_[0] &= ~0x00000004u; +} +inline void PandaLinkState::clear_orient() { + if (orient_ != NULL) orient_->::panda::PandaLinkState_Orientation::Clear(); + clear_has_orient(); +} +inline const ::panda::PandaLinkState_Orientation& PandaLinkState::orient() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.orient) + return orient_ != NULL ? *orient_ : *default_instance_->orient_; +} +inline ::panda::PandaLinkState_Orientation* PandaLinkState::mutable_orient() { + set_has_orient(); + if (orient_ == NULL) { + orient_ = new ::panda::PandaLinkState_Orientation; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.orient) + return orient_; +} +inline ::panda::PandaLinkState_Orientation* PandaLinkState::release_orient() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.orient) + clear_has_orient(); + ::panda::PandaLinkState_Orientation* temp = orient_; + orient_ = NULL; + return temp; +} +inline void PandaLinkState::set_allocated_orient(::panda::PandaLinkState_Orientation* orient) { + delete orient_; + orient_ = orient; + if (orient) { + set_has_orient(); + } else { + clear_has_orient(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.orient) +} + +// optional .panda.PandaLinkState.TwistLinear tl = 4; +inline bool PandaLinkState::has_tl() const { + return (_has_bits_[0] & 0x00000008u) != 0; +} +inline void PandaLinkState::set_has_tl() { + _has_bits_[0] |= 0x00000008u; +} +inline void PandaLinkState::clear_has_tl() { + _has_bits_[0] &= ~0x00000008u; +} +inline void PandaLinkState::clear_tl() { + if (tl_ != NULL) tl_->::panda::PandaLinkState_TwistLinear::Clear(); + clear_has_tl(); +} +inline const ::panda::PandaLinkState_TwistLinear& PandaLinkState::tl() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.tl) + return tl_ != NULL ? *tl_ : *default_instance_->tl_; +} +inline ::panda::PandaLinkState_TwistLinear* PandaLinkState::mutable_tl() { + set_has_tl(); + if (tl_ == NULL) { + tl_ = new ::panda::PandaLinkState_TwistLinear; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.tl) + return tl_; +} +inline ::panda::PandaLinkState_TwistLinear* PandaLinkState::release_tl() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.tl) + clear_has_tl(); + ::panda::PandaLinkState_TwistLinear* temp = tl_; + tl_ = NULL; + return temp; +} +inline void PandaLinkState::set_allocated_tl(::panda::PandaLinkState_TwistLinear* tl) { + delete tl_; + tl_ = tl; + if (tl) { + set_has_tl(); + } else { + clear_has_tl(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.tl) +} + +// optional .panda.PandaLinkState.TwistAngular ta = 5; +inline bool PandaLinkState::has_ta() const { + return (_has_bits_[0] & 0x00000010u) != 0; +} +inline void PandaLinkState::set_has_ta() { + _has_bits_[0] |= 0x00000010u; +} +inline void PandaLinkState::clear_has_ta() { + _has_bits_[0] &= ~0x00000010u; +} +inline void PandaLinkState::clear_ta() { + if (ta_ != NULL) ta_->::panda::PandaLinkState_TwistAngular::Clear(); + clear_has_ta(); +} +inline const ::panda::PandaLinkState_TwistAngular& PandaLinkState::ta() const { + // @@protoc_insertion_point(field_get:panda.PandaLinkState.ta) + return ta_ != NULL ? *ta_ : *default_instance_->ta_; +} +inline ::panda::PandaLinkState_TwistAngular* PandaLinkState::mutable_ta() { + set_has_ta(); + if (ta_ == NULL) { + ta_ = new ::panda::PandaLinkState_TwistAngular; + } + // @@protoc_insertion_point(field_mutable:panda.PandaLinkState.ta) + return ta_; +} +inline ::panda::PandaLinkState_TwistAngular* PandaLinkState::release_ta() { + // @@protoc_insertion_point(field_release:panda.PandaLinkState.ta) + clear_has_ta(); + ::panda::PandaLinkState_TwistAngular* temp = ta_; + ta_ = NULL; + return temp; +} +inline void PandaLinkState::set_allocated_ta(::panda::PandaLinkState_TwistAngular* ta) { + delete ta_; + ta_ = ta; + if (ta) { + set_has_ta(); + } else { + clear_has_ta(); + } + // @@protoc_insertion_point(field_set_allocated:panda.PandaLinkState.ta) +} + +#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace panda + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_linkstate_2eproto__INCLUDED diff --git a/src/robotconfig.pb.cc b/src/messages/robotconfig.pb.cc similarity index 100% rename from src/robotconfig.pb.cc rename to src/messages/robotconfig.pb.cc diff --git a/src/robotconfig.pb.h b/src/messages/robotconfig.pb.h similarity index 100% rename from src/robotconfig.pb.h rename to src/messages/robotconfig.pb.h diff --git a/src/SampleConstraintPlanner.cpp b/src/samples/SampleConstraintPlanner.cpp similarity index 53% rename from src/SampleConstraintPlanner.cpp rename to src/samples/SampleConstraintPlanner.cpp index 2698d0c42496e8a250c83cc68669e7cd34f074a6..4f442184ef3d8d1a11189f1bce2cbff7f8ed8847 100644 --- a/src/SampleConstraintPlanner.cpp +++ b/src/samples/SampleConstraintPlanner.cpp @@ -14,98 +14,7 @@ #include <moveit/trajectory_processing/iterative_time_parameterization.h> #include <trajectory_msgs/JointTrajectoryPoint.h> -int main(int argc, char **argv) -{ - ros::init(argc, argv, "move_group_interface_tutorial"); - ros::NodeHandle node_handle; - ros::AsyncSpinner spinner(1); - spinner.start(); - - std::cout << ">>>>>>>>>>>>>>>>> SLEEPING <<<<<<<<<<<<<<<< " << std::endl; - ros::Duration(5.0).sleep(); - std::cout << ">>>>>>>>>>>>>>>>> WAKING UP <<<<<<<<<<<<<<<< " << std::endl; - //moveit::planning_interface::MoveGroup group("arm_gp"); - moveit::planning_interface::MoveGroupInterface group("panda_arm"); - - moveit::planning_interface::PlanningSceneInterface planning_scene_interface; - - ros::Publisher display_publisher = node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true); - moveit_msgs::DisplayTrajectory display_trajectory; - - moveit::planning_interface::MoveGroupInterface::Plan plan; - group.setStartStateToCurrentState(); - - std::vector<geometry_msgs::Pose> waypoints; - - geometry_msgs::Pose target_pose = group.getCurrentPose().pose; - target_pose.position.x += 2.0; - target_pose.position.y += 5.0; - target_pose.position.z -= 2.0; - waypoints.push_back(target_pose); - - /*target_pose.position.y -= 0.0; - waypoints.push_back(target_pose); - - target_pose.position.z -= 0.08; - target_pose.position.y += 0.0; - target_pose.position.x -= 0.0; - waypoints.push_back(target_pose);*/ - - moveit_msgs::RobotTrajectory trajectory_msg; - group.setPlanningTime(10.0); - - double fraction = group.computeCartesianPath(waypoints, - 0.01, // eef_step - 0.0, // jump_threshold - trajectory_msg, false); - // The trajectory needs to be modified so it will include velocities as well. - // First to create a RobotTrajectory object - robot_trajectory::RobotTrajectory rt(group.getCurrentState()->getRobotModel(), "panda_arm"); - - // Second get a RobotTrajectory from trajectory - rt.setRobotTrajectoryMsg(*group.getCurrentState(), trajectory_msg); - - // Third create a IterativeParabolicTimeParameterization object - trajectory_processing::IterativeParabolicTimeParameterization iptp; - // Fourth compute computeTimeStamps - bool success = iptp.computeTimeStamps(rt); - ROS_INFO("Computed time stamp %s",success?"SUCCEDED":"FAILED"); - // Get RobotTrajectory_msg from RobotTrajectory - rt.getRobotTrajectoryMsg(trajectory_msg); - // Check trajectory_msg for velocities not empty - //std::cout << ">>>>>>>>>>>>>>>>> data before: " << trajectory_msg << std::endl; - - // adjust velocities, accelerations and time_from_start - for(int i = 0; i < trajectory_msg.joint_trajectory.points.size(); i++) - { - trajectory_msg.joint_trajectory.points[i].time_from_start.operator*=(5); - for(int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).velocities.size(); j++) - { - if(trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) != 0.0){ - trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) /= 5; - //trajectory_msg.joint_trajectory.points.at(i).velocities.at(j) = 0; - } - } - - for(int j = 0; j < trajectory_msg.joint_trajectory.points.at(i).accelerations.size(); j++) - { - trajectory_msg.joint_trajectory.points.at(i).accelerations.at(j) = - sqrt(std::abs(trajectory_msg.joint_trajectory.points.at(i).accelerations.at(j))); - } - } - - //std::cout << ">>>>>>>>>>>>>>>>> data after: " << trajectory_msg << std::endl; - - plan.trajectory_ = trajectory_msg; - ROS_INFO("Visualizing plan 4 (cartesian path) (%.2f%% acheived)",fraction * 100.0); - sleep(5.0); - - group.execute(plan); - - ros::shutdown(); - return 0; -} -/*int main(int argc, char** argv) +int main(int argc, char** argv) { ros::init(argc, argv, "CONSTRAINT PLANNER"); ros::NodeHandle node_handle; @@ -197,4 +106,4 @@ int main(int argc, char **argv) ros::shutdown(); return 0; -}*/ \ No newline at end of file +} \ No newline at end of file diff --git a/src/SampleTimedCartesianPlanner.cpp b/src/samples/SampleTimedCartesianPlanner.cpp similarity index 100% rename from src/SampleTimedCartesianPlanner.cpp rename to src/samples/SampleTimedCartesianPlanner.cpp diff --git a/src/tutorial/motion_planning_api_tutorial.cpp b/src/tutorial/motion_planning_api_tutorial.cpp new file mode 100644 index 0000000000000000000000000000000000000000..9e95aadb8f7f14d75eeb88ef81d5faf1555f1c2a --- /dev/null +++ b/src/tutorial/motion_planning_api_tutorial.cpp @@ -0,0 +1,352 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Sachin Chitta, Michael Lautman */ + +#include <pluginlib/class_loader.h> +#include <ros/ros.h> + +// MoveIt +#include <moveit/robot_model_loader/robot_model_loader.h> +#include <moveit/planning_interface/planning_interface.h> +#include <moveit/planning_scene/planning_scene.h> +#include <moveit/kinematic_constraints/utils.h> +#include <moveit_msgs/DisplayTrajectory.h> +#include <moveit_msgs/PlanningScene.h> +#include <moveit_visual_tools/moveit_visual_tools.h> + +#include <boost/scoped_ptr.hpp> + +int main(int argc, char** argv) +{ + const std::string node_name = "motion_planning_tutorial"; + ros::init(argc, argv, node_name); + ros::AsyncSpinner spinner(1); + spinner.start(); + ros::NodeHandle node_handle("~"); + + // BEGIN_TUTORIAL + // Start + // ^^^^^ + // Setting up to start using a planner is pretty easy. Planners are + // setup as plugins in MoveIt and you can use the ROS pluginlib + // interface to load any planner that you want to use. Before we + // can load the planner, we need two objects, a RobotModel and a + // PlanningScene. We will start by instantiating a `RobotModelLoader`_ + // object, which will look up the robot description on the ROS + // parameter server and construct a :moveit_core:`RobotModel` for us + // to use. + // + // .. _RobotModelLoader: + // http://docs.ros.org/indigo/api/moveit_ros_planning/html/classrobot__model__loader_1_1RobotModelLoader.html + const std::string PLANNING_GROUP = "panda_arm"; + robot_model_loader::RobotModelLoader robot_model_loader("robot_description"); + robot_model::RobotModelPtr robot_model = robot_model_loader.getModel(); + /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ + robot_state::RobotStatePtr robot_state(new robot_state::RobotState(robot_model)); + const robot_state::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); + + // Using the :moveit_core:`RobotModel`, we can construct a :planning_scene:`PlanningScene` + // that maintains the state of the world (including the robot). + planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); + + // Configure a valid robot state + planning_scene->getCurrentStateNonConst().setToDefaultValues(joint_model_group, "ready"); + + // We will now construct a loader to load a planner, by name. + // Note that we are using the ROS pluginlib library here. + boost::scoped_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager>> planner_plugin_loader; + planning_interface::PlannerManagerPtr planner_instance; + std::string planner_plugin_name; + + // We will get the name of planning plugin we want to load + // from the ROS parameter server, and then load the planner + // making sure to catch all exceptions. + if (!node_handle.getParam("planning_plugin", planner_plugin_name)) + ROS_FATAL_STREAM("Could not find planner plugin name"); + try + { + planner_plugin_loader.reset(new pluginlib::ClassLoader<planning_interface::PlannerManager>( + "moveit_core", "planning_interface::PlannerManager")); + } + catch (pluginlib::PluginlibException& ex) + { + ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); + } + try + { + planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); + if (!planner_instance->initialize(robot_model, node_handle.getNamespace())) + ROS_FATAL_STREAM("Could not initialize planner instance"); + ROS_INFO_STREAM("Using planning interface '" << planner_instance->getDescription() << "'"); + } + catch (pluginlib::PluginlibException& ex) + { + const std::vector<std::string>& classes = planner_plugin_loader->getDeclaredClasses(); + std::stringstream ss; + for (std::size_t i = 0; i < classes.size(); ++i) + ss << classes[i] << " "; + ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what() << std::endl + << "Available plugins: " << ss.str()); + } + + // Visualization + // ^^^^^^^^^^^^^ + // The package MoveItVisualTools provides many capabilities for visualizing objects, robots, + // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script. + namespace rvt = rviz_visual_tools; + moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0"); + visual_tools.loadRobotStatePub("/display_robot_state"); + visual_tools.enableBatchPublishing(); + visual_tools.deleteAllMarkers(); // clear all old markers + visual_tools.trigger(); + + /* Remote control is an introspection tool that allows users to step through a high level script + via buttons and keyboard shortcuts in RViz */ + visual_tools.loadRemoteControl(); + + /* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/ + Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); + text_pose.translation().z() = 1.75; + visual_tools.publishText(text_pose, "Motion Planning API Demo", rvt::WHITE, rvt::XLARGE); + + /* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */ + visual_tools.trigger(); + + /* We can also use visual_tools to wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); + + // Pose Goal + // ^^^^^^^^^ + // We will now create a motion plan request for the arm of the Panda + // specifying the desired pose of the end-effector as input. + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.trigger(); + planning_interface::MotionPlanRequest req; + planning_interface::MotionPlanResponse res; + geometry_msgs::PoseStamped pose; + pose.header.frame_id = "panda_link0"; + pose.pose.position.x = 0.3; + pose.pose.position.y = 0.4; + pose.pose.position.z = 0.75; + pose.pose.orientation.w = 1.0; + + // A tolerance of 0.01 m is specified in position + // and 0.01 radians in orientation + std::vector<double> tolerance_pose(3, 0.01); + std::vector<double> tolerance_angle(3, 0.01); + + // We will create the request as a constraint using a helper function available + // from the + // `kinematic_constraints`_ + // package. + // + // .. _kinematic_constraints: + // http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132 + moveit_msgs::Constraints pose_goal = + kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); + + req.group_name = PLANNING_GROUP; + req.goal_constraints.push_back(pose_goal); + + // We now construct a planning context that encapsulate the scene, + // the request and the response. We call the planner using this + // planning context + planning_interface::PlanningContextPtr context = + planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } + + // Visualize the result + // ^^^^^^^^^^^^^^^^^^^^ + ros::Publisher display_publisher = + node_handle.advertise<moveit_msgs::DisplayTrajectory>("/move_group/display_planned_path", 1, true); + moveit_msgs::DisplayTrajectory display_trajectory; + + /* Visualize the trajectory */ + moveit_msgs::MotionPlanResponse response; + res.getMessage(response); + + display_trajectory.trajectory_start = response.trajectory_start; + display_trajectory.trajectory.push_back(response.trajectory); + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + + /* Set the state in the planning scene to the final state of the last plan */ + robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + planning_scene->setCurrentState(*robot_state.get()); + + // Display the goal state + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.publishAxisLabeled(pose.pose, "goal_1"); + visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); + visual_tools.trigger(); + + /* We can also use visual_tools to wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo"); + + // Joint Space Goals + // ^^^^^^^^^^^^^^^^^ + // Now, setup a joint space goal + robot_state::RobotState goal_state(robot_model); + std::vector<double> joint_values = { -1.0, 0.7, 0.7, -1.5, -0.7, 2.0, 0.0 }; + goal_state.setJointGroupPositions(joint_model_group, joint_values); + moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); + req.goal_constraints.clear(); + req.goal_constraints.push_back(joint_goal); + + // Call the planner and visualize the trajectory + /* Re-construct the planning context */ + context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + /* Call the Planner */ + context->solve(res); + /* Check that the planning was successful */ + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } + /* Visualize the trajectory */ + res.getMessage(response); + display_trajectory.trajectory.push_back(response.trajectory); + + /* Now you should see two planned trajectories in series*/ + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + + /* We will add more goals. But first, set the state in the planning + scene to the final state of the last plan */ + robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + planning_scene->setCurrentState(*robot_state.get()); + + // Display the goal state + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.publishAxisLabeled(pose.pose, "goal_2"); + visual_tools.publishText(text_pose, "Joint Space Goal (2)", rvt::WHITE, rvt::XLARGE); + visual_tools.trigger(); + + /* Wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo"); + + /* Now, we go back to the first goal to prepare for orientation constrained planning */ + req.goal_constraints.clear(); + req.goal_constraints.push_back(pose_goal); + context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + context->solve(res); + res.getMessage(response); + + display_trajectory.trajectory.push_back(response.trajectory); + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + + /* Set the state in the planning scene to the final state of the last plan */ + robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + planning_scene->setCurrentState(*robot_state.get()); + + // Display the goal state + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.trigger(); + + /* Wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to continue the demo"); + + // Adding Path Constraints + // ^^^^^^^^^^^^^^^^^^^^^^^ + // Let's add a new pose goal again. This time we will also add a path constraint to the motion. + /* Let's create a new pose goal */ + + pose.pose.position.x = 0.32; + pose.pose.position.y = -0.25; + pose.pose.position.z = 0.65; + pose.pose.orientation.w = 1.0; + moveit_msgs::Constraints pose_goal_2 = + kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); + + /* Now, let's try to move to this new pose goal*/ + req.goal_constraints.clear(); + req.goal_constraints.push_back(pose_goal_2); + + /* But, let's impose a path constraint on the motion. + Here, we are asking for the end-effector to stay level*/ + geometry_msgs::QuaternionStamped quaternion; + quaternion.header.frame_id = "panda_link0"; + quaternion.quaternion.w = 1.0; + req.path_constraints = kinematic_constraints::constructGoalConstraints("panda_link8", quaternion); + + // Imposing path constraints requires the planner to reason in the space of possible positions of the end-effector + // (the workspace of the robot) + // because of this, we need to specify a bound for the allowed planning volume as well; + // Note: a default bound is automatically filled by the WorkspaceBounds request adapter (part of the OMPL pipeline, + // but that is not being used in this example). + // We use a bound that definitely includes the reachable space for the arm. This is fine because sampling is not done + // in this volume + // when planning for the arm; the bounds are only used to determine if the sampled configurations are valid. + req.workspace_parameters.min_corner.x = req.workspace_parameters.min_corner.y = + req.workspace_parameters.min_corner.z = -2.0; + req.workspace_parameters.max_corner.x = req.workspace_parameters.max_corner.y = + req.workspace_parameters.max_corner.z = 2.0; + + // Call the planner and visualize all the plans created so far. + context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + context->solve(res); + res.getMessage(response); + display_trajectory.trajectory.push_back(response.trajectory); + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + + /* Set the state in the planning scene to the final state of the last plan */ + robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + planning_scene->setCurrentState(*robot_state.get()); + + // Display the goal state + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.publishAxisLabeled(pose.pose, "goal_3"); + visual_tools.publishText(text_pose, "Orientation Constrained Motion Plan (3)", rvt::WHITE, rvt::XLARGE); + visual_tools.trigger(); + + // END_TUTORIAL + /* Wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to exit the demo"); + planner_instance.reset(); + + return 0; +} diff --git a/src/move_group_interface_tutorial.cpp b/src/tutorial/move_group_interface_tutorial.cpp similarity index 99% rename from src/move_group_interface_tutorial.cpp rename to src/tutorial/move_group_interface_tutorial.cpp index c98d8b26922f6137e73531b50e8fb33aa954b811..c61ef2c42fc984f1329340ea4a18c951088e58b6 100644 --- a/src/move_group_interface_tutorial.cpp +++ b/src/tutorial/move_group_interface_tutorial.cpp @@ -234,6 +234,9 @@ int main(int argc, char** argv) move_group.setPlanningTime(10.0); success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS); + + move_group.move(); + ROS_INFO_NAMED("tutorial", "Visualizing plan 3 (constraints) %s", success ? "" : "FAILED"); // Visualize the plan in RViz